32 #include <geometry_msgs/Twist.h> 33 #include <geometry_msgs/Pose.h> 41 using visualization_msgs::InteractiveMarker;
42 using visualization_msgs::InteractiveMarkerControl;
43 using visualization_msgs::InteractiveMarkerFeedback;
49 :
nh(
"~"),
server(
"twist_marker_server")
51 std::string cmd_vel_topic;
76 ROS_INFO(
"[twist_marker_server] Initialized.");
80 const InteractiveMarkerFeedback::ConstPtr &feedback);
102 const InteractiveMarkerFeedback::ConstPtr &feedback )
104 geometry_msgs::Twist vel;
107 double yaw =
tf::getYaw(feedback->pose.orientation);
142 InteractiveMarker int_marker;
144 int_marker.name =
robot_name +
"_twist_marker";
145 int_marker.description =
"twist controller for " +
robot_name;
148 InteractiveMarkerControl control;
150 control.orientation_mode = InteractiveMarkerControl::FIXED;
154 control.orientation.w = 1;
155 control.orientation.x = 1;
156 control.orientation.y = 0;
157 control.orientation.z = 0;
158 control.name =
"move_x";
159 control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
160 int_marker.controls.push_back(control);
164 control.orientation.w = 1;
165 control.orientation.x = 0;
166 control.orientation.y = 0;
167 control.orientation.z = 1;
168 control.name =
"move_y";
169 control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
170 int_marker.controls.push_back(control);
174 control.orientation.w = 1;
175 control.orientation.x = 0;
176 control.orientation.y = 1;
177 control.orientation.z = 0;
178 control.name =
"move_z";
179 control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
180 int_marker.controls.push_back(control);
183 control.orientation.w = 1;
184 control.orientation.x = 0;
185 control.orientation.y = 1;
186 control.orientation.z = 0;
187 control.name =
"rotate_z";
188 control.interaction_mode = InteractiveMarkerControl::ROTATE_AXIS;
189 int_marker.controls.push_back(control);
199 int main(
int argc,
char** argv)
void publish(const boost::shared_ptr< M > &message) const
static double getYaw(const Quaternion &bt_q)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
interactive_markers::InteractiveMarkerServer server
double max_angular_velocity
ROSCPP_DECL void spin(Spinner &spinner)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
std::map< std::string, double > linear_drive_scale_map
void processFeedback(const InteractiveMarkerFeedback::ConstPtr &feedback)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::map< std::string, double > max_negative_linear_velocity_map
void createInteractiveMarkers()
INTERACTIVE_MARKERS_PUBLIC void insert(const visualization_msgs::InteractiveMarker &int_marker)
int main(int argc, char **argv)
double angular_drive_scale
INTERACTIVE_MARKERS_PUBLIC void applyChanges()
bool getParam(const std::string &key, std::string &s) const
INTERACTIVE_MARKERS_PUBLIC bool setPose(const std::string &name, const geometry_msgs::Pose &pose, const std_msgs::Header &header=std_msgs::Header())
std::map< std::string, double > max_positive_linear_velocity_map