42 uint8_t
type = feedback->event_type;
44 if( type == vm::InteractiveMarkerFeedback::BUTTON_CLICK ||
45 type == vm::InteractiveMarkerFeedback::MOUSE_DOWN ||
46 type == vm::InteractiveMarkerFeedback::MOUSE_UP )
48 const char* type_str = (type == vm::InteractiveMarkerFeedback::BUTTON_CLICK ?
"button click" :
49 (type == vm::InteractiveMarkerFeedback::MOUSE_DOWN ?
"mouse down" :
"mouse up"));
51 if( feedback->mouse_point_valid )
53 ROS_INFO(
"%s at %f, %f, %f in frame %s",
55 feedback->mouse_point.x, feedback->mouse_point.y, feedback->mouse_point.z,
56 feedback->header.frame_id.c_str() );
63 else if( type == vm::InteractiveMarkerFeedback::POSE_UPDATE )
66 << feedback->pose.position.x <<
", " << feedback->pose.position.y
67 <<
", " << feedback->pose.position.z );
71 void makePoints( std::vector<geometry_msgs::Point>& points_out,
int num_points )
74 points_out.resize(num_points);
75 for(
int i = 0; i < num_points; i++ )
77 double angle = (i / (double) num_points * 50 * M_PI);
78 double height = (i / (double) num_points * 10);
79 points_out[i].x = radius * cos( angle );
80 points_out[i].y = radius * sin( angle );
81 points_out[i].z = height;
89 int_marker.header.frame_id =
"base_link";
90 int_marker.name =
name;
94 vm::Marker points_marker;
95 points_marker.type =
type;
96 points_marker.scale.x = scale;
97 points_marker.scale.y = scale;
98 points_marker.scale.z = scale;
99 points_marker.color.r = 0.5;
100 points_marker.color.g = 0.5;
101 points_marker.color.b = 0.5;
102 points_marker.color.a = 1.0;
103 makePoints( points_marker.points, num_points );
106 vm::InteractiveMarkerControl points_control;
107 points_control.always_visible =
true;
108 points_control.interaction_mode = vm::InteractiveMarkerControl::BUTTON;
109 points_control.markers.push_back( points_marker );
112 int_marker.controls.push_back( points_control );
118 rotate_control.name =
"move_x";
119 rotate_control.interaction_mode =
120 vm::InteractiveMarkerControl::MOVE_AXIS;
123 int_marker.controls.push_back(rotate_control);
125 int_marker.pose.position.x = x;
130 int main(
int argc,
char** argv)
int main(int argc, char **argv)
void processFeedback(const vm::InteractiveMarkerFeedbackConstPtr &feedback)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
ROSCPP_DECL void spin(Spinner &spinner)
vm::InteractiveMarker makeMarker(std::string name, std::string description, int32_t type, float x, int num_points=10000, float scale=0.1f)
void makePoints(std::vector< geometry_msgs::Point > &points_out, int num_points)
INTERACTIVE_MARKERS_PUBLIC void insert(const visualization_msgs::InteractiveMarker &int_marker)
#define ROS_INFO_STREAM(args)
INTERACTIVE_MARKERS_PUBLIC void applyChanges()