interactive_marker_utils.h
Go to the documentation of this file.
1 #ifndef _MARKER_UTILS_H_
2 #define _MARKER_UTILS_H_
3 
4 
5 #include <ros/ros.h>
6 
7 #include <tf/tf.h>
10 
12 
14 #include <jsk_interactive_marker/SetPose.h>
15 #include <jsk_interactive_marker/MarkerSetPose.h>
16 
17 #include <math.h>
18 #include <jsk_interactive_marker/MarkerMenu.h>
19 #include <jsk_interactive_marker/MarkerPose.h>
20 
21 #include <std_msgs/Int8.h>
22 #include "urdf_parser/urdf_parser.h"
23 #include <fstream>
24 
25 #include <kdl/frames_io.hpp>
26 #include <tf_conversions/tf_kdl.h>
27 
28 #if ROS_VERSION_MINIMUM(1,12,0) // kinetic
29 #include <urdf_model/types.h>
30 #include <urdf_world/types.h>
31 #else
32 namespace urdf {
41 }
42 #endif
43 
44 
45 using namespace urdf;
46 
47 namespace im_utils{
48  geometry_msgs::Transform Pose2Transform( const geometry_msgs::Pose pose_msg);
49  geometry_msgs::Pose Transform2Pose( const geometry_msgs::Transform tf_msg);
50  geometry_msgs::Pose UrdfPose2Pose( const urdf::Pose pose);
51 
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);
56  visualization_msgs::InteractiveMarkerControl makeMeshMarkerControl(const std::string &mesh_resource, const geometry_msgs::PoseStamped &stamped, geometry_msgs::Vector3 scale);
57  visualization_msgs::InteractiveMarkerControl makeMeshMarkerControl(const std::string &mesh_resource,
58  const geometry_msgs::PoseStamped &stamped, geometry_msgs::Vector3 scale, const std_msgs::ColorRGBA &color);
59  void addMeshLinksControl(visualization_msgs::InteractiveMarker &im, LinkConstSharedPtr link, KDL::Frame previous_frame, bool use_color, std_msgs::ColorRGBA color, double scale);
60  void addMeshLinksControl(visualization_msgs::InteractiveMarker &im, LinkConstSharedPtr link, KDL::Frame previous_frame, bool use_color, std_msgs::ColorRGBA color, double scale, bool root);
61 
62  ModelInterfaceSharedPtr getModelInterface(std::string model_file);
63  visualization_msgs::InteractiveMarker makeLinksMarker(LinkConstSharedPtr link, bool use_color, std_msgs::ColorRGBA color, geometry_msgs::PoseStamped marker_ps, geometry_msgs::Pose origin_pose);
64 
65  visualization_msgs::InteractiveMarker makeFingerControlMarker(const char *name, geometry_msgs::PoseStamped ps);
66  visualization_msgs::InteractiveMarker makeSandiaHandMarker(geometry_msgs::PoseStamped ps);
67 
68  visualization_msgs::Marker makeSandiaFinger0Marker(std::string frame_id);
69  visualization_msgs::Marker makeSandiaFinger1Marker(std::string frame_id);
70  visualization_msgs::Marker makeSandiaFinger2Marker(std::string frame_id);
71 
72  visualization_msgs::InteractiveMarker makeSandiaHandInteractiveMarker(geometry_msgs::PoseStamped ps, std::string hand, int finger, int link);
73 
74  std::string getRosPathFromModelPath(std::string path);
75  std::string getRosPathFromFullPath(std::string path);
76  std::string getFullPathFromModelPath(std::string path);
77  std::string getFilePathFromRosPath( std::string rospath);
78 
79  geometry_msgs::Pose getPose( XmlRpc::XmlRpcValue val);
80  double getXmlValue( XmlRpc::XmlRpcValue val );
81 }
82 #endif
im_utils::makeCylinderMarkerControl
visualization_msgs::InteractiveMarkerControl makeCylinderMarkerControl(const geometry_msgs::PoseStamped &stamped, double length, double radius, const std_msgs::ColorRGBA &color, bool use_color)
Definition: interactive_marker_utils.cpp:55
im_utils::Pose2Transform
geometry_msgs::Transform Pose2Transform(const geometry_msgs::Pose pose_msg)
Definition: interactive_marker_utils.cpp:20
urdf::CylinderConstSharedPtr
boost::shared_ptr< const Cylinder > CylinderConstSharedPtr
Definition: interactive_marker_utils.h:38
im_utils::getRosPathFromModelPath
std::string getRosPathFromModelPath(std::string path)
Definition: interactive_marker_utils.cpp:493
scale
scale
boost::shared_ptr< ModelInterface >
im_utils::getXmlValue
double getXmlValue(XmlRpc::XmlRpcValue val)
Definition: interactive_marker_utils.cpp:639
ros.h
im_utils::makeLinksMarker
visualization_msgs::InteractiveMarker makeLinksMarker(LinkConstSharedPtr link, bool use_color, std_msgs::ColorRGBA color, geometry_msgs::PoseStamped marker_ps, geometry_msgs::Pose origin_pose)
Definition: interactive_marker_utils.cpp:281
menu_handler.h
im_utils::makeBoxMarkerControl
visualization_msgs::InteractiveMarkerControl makeBoxMarkerControl(const geometry_msgs::PoseStamped &stamped, Vector3 dim, const std_msgs::ColorRGBA &color, bool use_color)
Definition: interactive_marker_utils.cpp:73
im_utils::makeSphereMarkerControl
visualization_msgs::InteractiveMarkerControl makeSphereMarkerControl(const geometry_msgs::PoseStamped &stamped, double rad, const std_msgs::ColorRGBA &color, bool use_color)
Definition: interactive_marker_utils.cpp:92
transform_broadcaster.h
urdf::MeshConstSharedPtr
boost::shared_ptr< const Mesh > MeshConstSharedPtr
Definition: interactive_marker_utils.h:37
urdf::SphereConstSharedPtr
boost::shared_ptr< const Sphere > SphereConstSharedPtr
Definition: interactive_marker_utils.h:40
pose
pose
im_utils::makeSandiaFinger1Marker
visualization_msgs::Marker makeSandiaFinger1Marker(std::string frame_id)
Definition: interactive_marker_utils.cpp:447
im_utils::makeFingerControlMarker
visualization_msgs::InteractiveMarker makeFingerControlMarker(const char *name, geometry_msgs::PoseStamped ps)
Definition: interactive_marker_utils.cpp:299
im_utils::makeSandiaHandInteractiveMarker
visualization_msgs::InteractiveMarker makeSandiaHandInteractiveMarker(geometry_msgs::PoseStamped ps, std::string hand, int finger, int link)
Definition: interactive_marker_utils.cpp:383
im_utils::makeMeshMarkerControl
visualization_msgs::InteractiveMarkerControl makeMeshMarkerControl(const std::string &mesh_resource, const geometry_msgs::PoseStamped &stamped, geometry_msgs::Vector3 scale, const std_msgs::ColorRGBA &color)
Definition: interactive_marker_utils.cpp:140
im_utils::addMeshLinksControl
void addMeshLinksControl(visualization_msgs::InteractiveMarker &im, LinkConstSharedPtr link, KDL::Frame previous_frame, bool use_color, std_msgs::ColorRGBA color, double scale, bool root)
Definition: interactive_marker_utils.cpp:150
im_utils::getRosPathFromFullPath
std::string getRosPathFromFullPath(std::string path)
Definition: interactive_marker_utils.cpp:497
im_utils::getModelInterface
ModelInterfaceSharedPtr getModelInterface(std::string model_file)
Definition: interactive_marker_utils.cpp:258
urdf::LinkSharedPtr
boost::shared_ptr< Link > LinkSharedPtr
Definition: interactive_marker_utils.h:34
transform_listener.h
im_utils::getFilePathFromRosPath
std::string getFilePathFromRosPath(std::string rospath)
Definition: interactive_marker_utils.cpp:592
tf.h
im_utils::UrdfPose2Pose
geometry_msgs::Pose UrdfPose2Pose(const urdf::Pose pose)
Definition: interactive_marker_utils.cpp:38
urdf::BoxConstSharedPtr
boost::shared_ptr< const Box > BoxConstSharedPtr
Definition: interactive_marker_utils.h:39
dummy_camera.frame_id
frame_id
Definition: dummy_camera.py:10
interactive_marker_server.h
urdf::VisualSharedPtr
boost::shared_ptr< Visual > VisualSharedPtr
Definition: interactive_marker_utils.h:36
urdf::ModelInterfaceSharedPtr
boost::shared_ptr< ModelInterface > ModelInterfaceSharedPtr
Definition: interactive_marker_interface.h:23
urdf
length
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
im_utils::makeSandiaHandMarker
visualization_msgs::InteractiveMarker makeSandiaHandMarker(geometry_msgs::PoseStamped ps)
im_utils
Definition: interactive_marker_utils.h:47
tf_kdl.h
urdf::LinkConstSharedPtr
boost::shared_ptr< const Link > LinkConstSharedPtr
Definition: interactive_marker_utils.h:35
im_utils::makeSandiaFinger0Marker
visualization_msgs::Marker makeSandiaFinger0Marker(std::string frame_id)
Definition: interactive_marker_utils.cpp:423
radius
GLdouble radius
root
root
im_utils::Transform2Pose
geometry_msgs::Pose Transform2Pose(const geometry_msgs::Transform tf_msg)
Definition: interactive_marker_utils.cpp:29
im_utils::getPose
geometry_msgs::Pose getPose(XmlRpc::XmlRpcValue val)
Definition: interactive_marker_utils.cpp:614
im_utils::getFullPathFromModelPath
std::string getFullPathFromModelPath(std::string path)
Definition: interactive_marker_utils.cpp:549
XmlRpc::XmlRpcValue
im_utils::makeSandiaFinger2Marker
visualization_msgs::Marker makeSandiaFinger2Marker(std::string frame_id)
Definition: interactive_marker_utils.cpp:470


jsk_interactive_marker
Author(s): furuta
autogenerated on Sat Jun 1 2024 02:47:23