#include <ros/ros.h>
#include <tf/tf.h>
#include <tf/transform_listener.h>
#include <tf/transform_broadcaster.h>
#include <interactive_markers/interactive_marker_server.h>
#include <interactive_markers/menu_handler.h>
#include <jsk_interactive_marker/SetPose.h>
#include <jsk_interactive_marker/MarkerSetPose.h>
#include <math.h>
#include <jsk_interactive_marker/MarkerMenu.h>
#include <jsk_interactive_marker/MarkerPose.h>
#include <std_msgs/Int8.h>
Go to the source code of this file.
Functions | |
std::string | getFilePathFromRosPath (std::string rospath) |
std::string | getFullPathFromModelPath (std::string path) |
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::InteractiveMarker | makeFingerControlMarker (const char *name, geometry_msgs::PoseStamped ps) |
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) |
std::string getFilePathFromRosPath | ( | std::string | rospath | ) |
Definition at line 281 of file interactive_marker_utils.cpp.
Definition at line 242 of file interactive_marker_utils.cpp.
Definition at line 364 of file door_foot.cpp.
Definition at line 209 of file interactive_marker_utils.cpp.
Definition at line 205 of file interactive_marker_utils.cpp.
double getXmlValue | ( | XmlRpc::XmlRpcValue | val | ) |
Definition at line 380 of file door_foot.cpp.
visualization_msgs::InteractiveMarker makeFingerControlMarker | ( | const char * | name, |
geometry_msgs::PoseStamped | ps | ||
) |
Definition at line 11 of file interactive_marker_utils.cpp.
visualization_msgs::Marker makeSandiaFinger0Marker | ( | std::string | frame_id | ) |
Definition at line 135 of file interactive_marker_utils.cpp.
visualization_msgs::Marker makeSandiaFinger1Marker | ( | std::string | frame_id | ) |
Definition at line 159 of file interactive_marker_utils.cpp.
visualization_msgs::Marker makeSandiaFinger2Marker | ( | std::string | frame_id | ) |
Definition at line 182 of file interactive_marker_utils.cpp.
visualization_msgs::InteractiveMarker makeSandiaHandInteractiveMarker | ( | geometry_msgs::PoseStamped | ps, |
std::string | hand, | ||
int | finger, | ||
int | link | ||
) |
Definition at line 95 of file interactive_marker_utils.cpp.
visualization_msgs::InteractiveMarker makeSandiaHandMarker | ( | geometry_msgs::PoseStamped | ps | ) |