Using LINE_LIST as an Interactive Marker button in rviz.
Hello all, I'm trying to use LINE_LIST as an interactive marker button in rviz but am unable to do so. In the following sample code if I replace the marker type of the variable line_list from LINE_LIST to something else, for example, SPHERE, CUBE, or even CUBE_LIST or SPHERE_LIST it would work as a button but it doesn't work in the case of LINE_LIST:
#include <ros/ros.h>
#include <interactive_markers/interactive_marker_server.h>
#include <tf/transform_broadcaster.h>
#include <tf/tf.h>
void processFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
{
ROS_INFO("feedback->pose.position.x=%f, feedback->pose.position.y=%f, feedback->pose.position.z=%f", feedback->pose.position.x, feedback->pose.position.y, feedback->pose.position.z);
}
int main(int argc, char ** argv)
{
ros::init(argc, argv, "line_list_interactive_marker");
ros::NodeHandle n;
ros::Publisher marker_pub = n.advertise<visualization_msgs::Marker>("visualization_msgs", 1);
interactive_markers::InteractiveMarkerServer server("line_list_interactive_marker_server");
visualization_msgs::InteractiveMarker int_marker;
int_marker.header.frame_id = "/my_frame";
int_marker.name="my_marker";
visualization_msgs::Marker line_list;
line_list.type = visualization_msgs::Marker::LINE_LIST;
line_list.color.r=1.0f;
line_list.color.a=1.0f;
line_list.scale.x = line_list.scale.y = line_list.scale.z = 0.1;
geometry_msgs::Point point;
point.x = 0.9;
point.y = 0.9;
line_list.points.push_back(point);
point.x = 1;
point.y = 1;
point.z = 0;
line_list.points.push_back(point);
point.x = 0;
point.y = 0;
line_list.points.push_back(point);
point.x = -3;
point.y = 3;
line_list.points.push_back(point);
visualization_msgs::InteractiveMarkerControl line_list_control;
line_list_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
line_list_control.name = "line_list_control";
line_list_control.always_visible = true;
line_list_control.markers.push_back(line_list);
int_marker.controls.push_back(line_list_control);
visualization_msgs::InteractiveMarkerControl a;
a.name = "a";
a.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
int_marker.controls.push_back(a);
server.insert(int_marker, processFeedback);
server.applyChanges();
ros::spin();
return 0;
}
Also I want to know is there any possible way to get the mouse position when the user clicks on a button marker? I know through the InteractiveMarkerFeedbackConstPtr structure argument of the callback I can get the position of the marker but it does not give the location of mouse click.
Thanks.