1 #ifndef _MARKER_UTILS_H_
2 #define _MARKER_UTILS_H_
14 #include <jsk_interactive_marker/SetPose.h>
15 #include <jsk_interactive_marker/MarkerSetPose.h>
18 #include <jsk_interactive_marker/MarkerMenu.h>
19 #include <jsk_interactive_marker/MarkerPose.h>
21 #include <std_msgs/Int8.h>
22 #include "urdf_parser/urdf_parser.h"
25 #include <kdl/frames_io.hpp>
28 #if ROS_VERSION_MINIMUM(1,12,0) // kinetic
29 #include <urdf_model/types.h>
30 #include <urdf_world/types.h>
48 geometry_msgs::Transform
Pose2Transform(
const geometry_msgs::Pose pose_msg);
49 geometry_msgs::Pose
Transform2Pose(
const geometry_msgs::Transform tf_msg);
52 visualization_msgs::InteractiveMarkerControl
makeCylinderMarkerControl(
const geometry_msgs::PoseStamped &stamped,
double length,
double radius,
const std_msgs::ColorRGBA &color,
bool use_color);
53 visualization_msgs::InteractiveMarkerControl
makeBoxMarkerControl(
const geometry_msgs::PoseStamped &stamped, Vector3 dim,
const std_msgs::ColorRGBA &color,
bool use_color);
54 visualization_msgs::InteractiveMarkerControl
makeSphereMarkerControl(
const geometry_msgs::PoseStamped &stamped,
double rad,
const std_msgs::ColorRGBA &color,
bool use_color);
55 visualization_msgs::InteractiveMarkerControl
makeMeshMarkerControl(
const std::string &
mesh_resource,
const geometry_msgs::PoseStamped &stamped, geometry_msgs::Vector3
scale,
const std_msgs::ColorRGBA &color,
bool use_color);
58 const geometry_msgs::PoseStamped &stamped, geometry_msgs::Vector3
scale,
const std_msgs::ColorRGBA &color);
63 visualization_msgs::InteractiveMarker
makeLinksMarker(
LinkConstSharedPtr link,
bool use_color, std_msgs::ColorRGBA color, geometry_msgs::PoseStamped marker_ps, geometry_msgs::Pose origin_pose);