Project

General

Profile

Statistics
| Branch: | Revision:

root / vision / src / rviz_interactive_target.cpp @ bb70c69d

History | View | Annotate | Download (2 KB)

1
#include <ros/ros.h>
2
#include <string.h>
3
#include <geometry_msgs/Quaternion.h>
4
#include <interactive_markers/interactive_marker_server.h>
5
#include <functional>
6

    
7
using namespace std;
8
using namespace visualization_msgs;
9

    
10
/* TODO:
11
 * -replace the three MOVE_AXIS directions with one MOVE_AXIS and one MOVE_PLANE
12
 * -have it constantly publish current position, instead of only publishing
13
 *  when the marker is moved
14
 */
15

    
16
class Marker3DOF
17
{
18
public:
19
  Marker3DOF(interactive_markers::InteractiveMarkerServer& server);
20
  void processFeedback(const InteractiveMarkerFeedbackConstPtr& feedback);
21
private:
22
  void addControl(string name, float x, float y, float z, float w);
23
  ros::NodeHandle nh;
24
  InteractiveMarker marker;
25
  ros::Publisher pub;
26
};
27

    
28
Marker3DOF::Marker3DOF(interactive_markers::InteractiveMarkerServer& server)
29
{
30
  marker.header.frame_id = "/quadrotor";
31
  marker.pose.position.x = 5;
32
  marker.pose.position.y = 0;
33
  marker.pose.position.z = 0;
34
  marker.scale = 1;
35
  marker.name = "target";
36
  addControl("target_x", 1, 0, 0, 1);
37
  addControl("target_y", 0, 1, 0, 1);
38
  addControl("target_z", 0, 0, 1, 1);
39
  server.insert(marker);
40
  server.setCallback("target", bind(&Marker3DOF::processFeedback, this, _1));
41
  server.applyChanges();
42
  pub = nh.advertise<geometry_msgs::Point>("/v2v3_converter/target_3d", 100);
43
}
44

    
45
void Marker3DOF::addControl(string name, float x, float y, float z, float w)
46
{
47
  InteractiveMarkerControl control;
48
  control.orientation.x = x;
49
  control.orientation.y = y;
50
  control.orientation.z = z;
51
  control.orientation.w = w;
52
  control.name = name;
53
  control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
54
  marker.controls.push_back(control);
55
}
56

    
57
void Marker3DOF::processFeedback(const InteractiveMarkerFeedbackConstPtr&
58
    feedback)
59
{
60
  pub.publish(feedback->pose.position);
61
}
62

    
63
int main(int argc, char **argv)
64
{
65
  ros::init(argc, argv, "rviz_interactive_targets");
66
  interactive_markers::InteractiveMarkerServer server(
67
      "rviz_interactive_targets");
68
  Marker3DOF marker(server);
69
  ros::spin();
70
  return 0;
71
}