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")
74 ROS_INFO(
"[twist_marker_server] Initialized.");
78 const InteractiveMarkerFeedback::ConstPtr &feedback);
100 const InteractiveMarkerFeedback::ConstPtr &feedback )
102 geometry_msgs::Twist vel;
105 double yaw =
tf::getYaw(feedback->pose.orientation);
140 InteractiveMarker int_marker;
142 int_marker.name =
robot_name +
"_twist_marker";
143 int_marker.description =
"twist controller for " +
robot_name;
146 InteractiveMarkerControl control;
148 control.orientation_mode = InteractiveMarkerControl::FIXED;
152 control.orientation.w = 1;
153 control.orientation.x = 1;
154 control.orientation.y = 0;
155 control.orientation.z = 0;
156 control.name =
"move_x";
157 control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
158 int_marker.controls.push_back(control);
162 control.orientation.w = 1;
163 control.orientation.x = 0;
164 control.orientation.y = 0;
165 control.orientation.z = 1;
166 control.name =
"move_y";
167 control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
168 int_marker.controls.push_back(control);
172 control.orientation.w = 1;
173 control.orientation.x = 0;
174 control.orientation.y = 1;
175 control.orientation.z = 0;
176 control.name =
"move_z";
177 control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
178 int_marker.controls.push_back(control);
181 control.orientation.w = 1;
182 control.orientation.x = 0;
183 control.orientation.y = 1;
184 control.orientation.z = 0;
185 control.name =
"rotate_z";
186 control.interaction_mode = InteractiveMarkerControl::ROTATE_AXIS;
187 int_marker.controls.push_back(control);
197 int main(
int argc,
char** argv)
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
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
bool getParam(const std::string &key, std::string &s) 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()
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