Functions | |
void | addMeshLinksControl (visualization_msgs::InteractiveMarker &im, LinkConstSharedPtr link, KDL::Frame previous_frame, bool use_color, std_msgs::ColorRGBA color, double scale) |
void | addMeshLinksControl (visualization_msgs::InteractiveMarker &im, LinkConstSharedPtr link, KDL::Frame previous_frame, bool use_color, std_msgs::ColorRGBA color, double scale, bool root) |
std::string | getFilePathFromRosPath (std::string rospath) |
std::string | getFullPathFromModelPath (std::string path) |
ModelInterfaceSharedPtr | getModelInterface (std::string model_file) |
geometry_msgs::Pose | getPose (XmlRpc::XmlRpcValue val) |
std::string | getRosPathFromFullPath (std::string path) |
std::string | getRosPathFromModelPath (std::string path) |
double | getXmlValue (XmlRpc::XmlRpcValue val) |
visualization_msgs::InteractiveMarkerControl | makeBoxMarkerControl (const geometry_msgs::PoseStamped &stamped, Vector3 dim, const std_msgs::ColorRGBA &color, bool use_color) |
visualization_msgs::InteractiveMarkerControl | makeCylinderMarkerControl (const geometry_msgs::PoseStamped &stamped, double length, double radius, const std_msgs::ColorRGBA &color, bool use_color) |
visualization_msgs::InteractiveMarker | makeFingerControlMarker (const char *name, geometry_msgs::PoseStamped ps) |
visualization_msgs::InteractiveMarker | makeLinksMarker (LinkConstSharedPtr link, bool use_color, std_msgs::ColorRGBA color, geometry_msgs::PoseStamped marker_ps, geometry_msgs::Pose origin_pose) |
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) |
visualization_msgs::InteractiveMarkerControl | makeMeshMarkerControl (const std::string &mesh_resource, const geometry_msgs::PoseStamped &stamped, geometry_msgs::Vector3 scale) |
visualization_msgs::InteractiveMarkerControl | makeMeshMarkerControl (const std::string &mesh_resource, const geometry_msgs::PoseStamped &stamped, geometry_msgs::Vector3 scale, const std_msgs::ColorRGBA &color) |
visualization_msgs::Marker | makeSandiaFinger0Marker (std::string frame_id) |
visualization_msgs::Marker | makeSandiaFinger1Marker (std::string frame_id) |
visualization_msgs::Marker | makeSandiaFinger2Marker (std::string frame_id) |
visualization_msgs::InteractiveMarker | makeSandiaHandInteractiveMarker (geometry_msgs::PoseStamped ps, std::string hand, int finger, int link) |
visualization_msgs::InteractiveMarker | makeSandiaHandMarker (geometry_msgs::PoseStamped ps) |
visualization_msgs::InteractiveMarkerControl | makeSphereMarkerControl (const geometry_msgs::PoseStamped &stamped, double rad, const std_msgs::ColorRGBA &color, bool use_color) |
geometry_msgs::Transform | Pose2Transform (const geometry_msgs::Pose pose_msg) |
geometry_msgs::Pose | Transform2Pose (const geometry_msgs::Transform tf_msg) |
geometry_msgs::Pose | UrdfPose2Pose (const urdf::Pose pose) |
void im_utils::addMeshLinksControl | ( | visualization_msgs::InteractiveMarker & | im, |
LinkConstSharedPtr | link, | ||
KDL::Frame | previous_frame, | ||
bool | use_color, | ||
std_msgs::ColorRGBA | color, | ||
double | scale | ||
) |
Definition at line 146 of file interactive_marker_utils.cpp.
void im_utils::addMeshLinksControl | ( | visualization_msgs::InteractiveMarker & | im, |
LinkConstSharedPtr | link, | ||
KDL::Frame | previous_frame, | ||
bool | use_color, | ||
std_msgs::ColorRGBA | color, | ||
double | scale, | ||
bool | root | ||
) |
Definition at line 150 of file interactive_marker_utils.cpp.
Definition at line 592 of file interactive_marker_utils.cpp.
Definition at line 549 of file interactive_marker_utils.cpp.
ModelInterfaceSharedPtr im_utils::getModelInterface | ( | std::string | model_file | ) |
Definition at line 258 of file interactive_marker_utils.cpp.
Definition at line 614 of file interactive_marker_utils.cpp.
Definition at line 497 of file interactive_marker_utils.cpp.
Definition at line 493 of file interactive_marker_utils.cpp.
double im_utils::getXmlValue | ( | XmlRpc::XmlRpcValue | val | ) |
Definition at line 639 of file interactive_marker_utils.cpp.
visualization_msgs::InteractiveMarkerControl im_utils::makeBoxMarkerControl | ( | const geometry_msgs::PoseStamped & | stamped, |
Vector3 | dim, | ||
const std_msgs::ColorRGBA & | color, | ||
bool | use_color | ||
) |
Definition at line 73 of file interactive_marker_utils.cpp.
visualization_msgs::InteractiveMarkerControl im_utils::makeCylinderMarkerControl | ( | const geometry_msgs::PoseStamped & | stamped, |
double | length, | ||
double | radius, | ||
const std_msgs::ColorRGBA & | color, | ||
bool | use_color | ||
) |
Definition at line 55 of file interactive_marker_utils.cpp.
visualization_msgs::InteractiveMarker im_utils::makeFingerControlMarker | ( | const char * | name, |
geometry_msgs::PoseStamped | ps | ||
) |
Definition at line 299 of file interactive_marker_utils.cpp.
visualization_msgs::InteractiveMarker im_utils::makeLinksMarker | ( | LinkConstSharedPtr | link, |
bool | use_color, | ||
std_msgs::ColorRGBA | color, | ||
geometry_msgs::PoseStamped | marker_ps, | ||
geometry_msgs::Pose | origin_pose | ||
) |
Definition at line 281 of file interactive_marker_utils.cpp.
visualization_msgs::InteractiveMarkerControl im_utils::makeMeshMarkerControl | ( | const std::string & | mesh_resource, |
const geometry_msgs::PoseStamped & | stamped, | ||
geometry_msgs::Vector3 | scale, | ||
const std_msgs::ColorRGBA & | color, | ||
bool | use_color | ||
) |
Definition at line 112 of file interactive_marker_utils.cpp.
visualization_msgs::InteractiveMarkerControl im_utils::makeMeshMarkerControl | ( | const std::string & | mesh_resource, |
const geometry_msgs::PoseStamped & | stamped, | ||
geometry_msgs::Vector3 | scale | ||
) |
Definition at line 130 of file interactive_marker_utils.cpp.
visualization_msgs::InteractiveMarkerControl im_utils::makeMeshMarkerControl | ( | const std::string & | mesh_resource, |
const geometry_msgs::PoseStamped & | stamped, | ||
geometry_msgs::Vector3 | scale, | ||
const std_msgs::ColorRGBA & | color | ||
) |
Definition at line 140 of file interactive_marker_utils.cpp.
visualization_msgs::Marker im_utils::makeSandiaFinger0Marker | ( | std::string | frame_id | ) |
Definition at line 423 of file interactive_marker_utils.cpp.
visualization_msgs::Marker im_utils::makeSandiaFinger1Marker | ( | std::string | frame_id | ) |
Definition at line 447 of file interactive_marker_utils.cpp.
visualization_msgs::Marker im_utils::makeSandiaFinger2Marker | ( | std::string | frame_id | ) |
Definition at line 470 of file interactive_marker_utils.cpp.
visualization_msgs::InteractiveMarker im_utils::makeSandiaHandInteractiveMarker | ( | geometry_msgs::PoseStamped | ps, |
std::string | hand, | ||
int | finger, | ||
int | link | ||
) |
Definition at line 383 of file interactive_marker_utils.cpp.
visualization_msgs::InteractiveMarker im_utils::makeSandiaHandMarker | ( | geometry_msgs::PoseStamped | ps | ) |
visualization_msgs::InteractiveMarkerControl im_utils::makeSphereMarkerControl | ( | const geometry_msgs::PoseStamped & | stamped, |
double | rad, | ||
const std_msgs::ColorRGBA & | color, | ||
bool | use_color | ||
) |
Definition at line 92 of file interactive_marker_utils.cpp.
geometry_msgs::Transform im_utils::Pose2Transform | ( | const geometry_msgs::Pose | pose_msg | ) |
Definition at line 20 of file interactive_marker_utils.cpp.
geometry_msgs::Pose im_utils::Transform2Pose | ( | const geometry_msgs::Transform | tf_msg | ) |
Definition at line 29 of file interactive_marker_utils.cpp.
geometry_msgs::Pose im_utils::UrdfPose2Pose | ( | const urdf::Pose | pose | ) |
Definition at line 38 of file interactive_marker_utils.cpp.