46 void processFeedback(
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback )
48 switch ( feedback->event_type )
50 case visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE:
54 tf::Vector3 fb_pos(feedback->pose.position.x, feedback->pose.position.y, feedback->pose.position.z);
55 unsigned index = atoi( feedback->marker_name.c_str() );
64 for (
unsigned i=0; i<positions.size(); i++ )
66 float d = fb_pos.
distance( positions[i] );
67 float t = 1 / (d*5.0+1.0) - 0.2;
70 positions[i] += t * fb_delta;
74 positions[i] = fb_pos;
77 geometry_msgs::Pose pose;
78 pose.position.
x = positions[i].x();
79 pose.position.y = positions[i].y();
80 pose.position.z = positions[i].z();
84 server->setPose( s.str(), pose );
91 server->applyChanges();
96 InteractiveMarkerControl control;
97 control.always_visible =
true;
98 control.orientation_mode = InteractiveMarkerControl::VIEW_FACING;
99 control.interaction_mode = InteractiveMarkerControl::MOVE_PLANE;
100 control.independent_marker_orientation =
true;
104 marker.type = Marker::CUBE;
105 marker.scale.x = msg.scale;
106 marker.scale.y = msg.scale;
107 marker.scale.z = msg.scale;
108 marker.color.r = 0.65+0.7*msg.pose.position.x;
109 marker.color.g = 0.65+0.7*msg.pose.position.y;
110 marker.color.b = 0.65+0.7*msg.pose.position.z;
111 marker.color.a = 1.0;
113 control.markers.push_back( marker );
114 msg.controls.push_back( control );
116 return msg.controls.back();
122 int side_length = 10;
123 float step = 1.0/ (float)side_length;
126 positions.reserve( side_length*side_length*side_length );
128 for (
double x=-0.5; x<0.5; x+=step )
130 for (
double y=-0.5; y<0.5; y+=step )
132 for (
double z=0.0; z<1.0; z+=step )
135 int_marker.header.frame_id =
"base_link";
136 int_marker.scale = step;
138 int_marker.pose.position.x = x;
139 int_marker.pose.position.y = y;
140 int_marker.pose.position.z = z;
146 int_marker.name = s.str();
150 server->insert( int_marker );
159 int main(
int argc,
char** argv)
169 server->applyChanges();
std::vector< tf::Vector3 > positions
void processFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
ROSCPP_DECL void spin(Spinner &spinner)
TFSIMD_FORCE_INLINE const tfScalar & x() const
boost::shared_ptr< interactive_markers::InteractiveMarkerServer > server
#define ROS_INFO_STREAM(args)
int main(int argc, char **argv)
InteractiveMarkerControl & makeBoxControl(InteractiveMarker &msg)