Namespaces | Typedefs | Functions
interactive_marker_utils.h File Reference
#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>
#include "urdf_parser/urdf_parser.h"
#include <fstream>
#include <kdl/frames_io.hpp>
#include <tf_conversions/tf_kdl.h>
Include dependency graph for interactive_marker_utils.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

 im_utils
 
 urdf
 

Typedefs

typedef boost::shared_ptr< const Box > urdf::BoxConstSharedPtr
 
typedef boost::shared_ptr< const Cylinder > urdf::CylinderConstSharedPtr
 
typedef boost::shared_ptr< const Link > urdf::LinkConstSharedPtr
 
typedef boost::shared_ptr< Link > urdf::LinkSharedPtr
 
typedef boost::shared_ptr< const Mesh > urdf::MeshConstSharedPtr
 
typedef boost::shared_ptr< const Sphere > urdf::SphereConstSharedPtr
 
typedef boost::shared_ptr< Visual > urdf::VisualSharedPtr
 

Functions

void im_utils::addMeshLinksControl (visualization_msgs::InteractiveMarker &im, LinkConstSharedPtr link, KDL::Frame previous_frame, bool use_color, std_msgs::ColorRGBA color, double scale)
 
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)
 
std::string im_utils::getFilePathFromRosPath (std::string rospath)
 
std::string im_utils::getFullPathFromModelPath (std::string path)
 
ModelInterfaceSharedPtr im_utils::getModelInterface (std::string model_file)
 
geometry_msgs::Pose im_utils::getPose (XmlRpc::XmlRpcValue val)
 
std::string im_utils::getRosPathFromFullPath (std::string path)
 
std::string im_utils::getRosPathFromModelPath (std::string path)
 
double im_utils::getXmlValue (XmlRpc::XmlRpcValue val)
 
visualization_msgs::InteractiveMarkerControl im_utils::makeBoxMarkerControl (const geometry_msgs::PoseStamped &stamped, Vector3 dim, const std_msgs::ColorRGBA &color, bool use_color)
 
visualization_msgs::InteractiveMarkerControl im_utils::makeCylinderMarkerControl (const geometry_msgs::PoseStamped &stamped, double length, double radius, const std_msgs::ColorRGBA &color, bool use_color)
 
visualization_msgs::InteractiveMarker im_utils::makeFingerControlMarker (const char *name, geometry_msgs::PoseStamped ps)
 
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)
 
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)
 
visualization_msgs::InteractiveMarkerControl im_utils::makeMeshMarkerControl (const std::string &mesh_resource, const geometry_msgs::PoseStamped &stamped, geometry_msgs::Vector3 scale)
 
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)
 
visualization_msgs::Marker im_utils::makeSandiaFinger0Marker (std::string frame_id)
 
visualization_msgs::Marker im_utils::makeSandiaFinger1Marker (std::string frame_id)
 
visualization_msgs::Marker im_utils::makeSandiaFinger2Marker (std::string frame_id)
 
visualization_msgs::InteractiveMarker im_utils::makeSandiaHandInteractiveMarker (geometry_msgs::PoseStamped ps, std::string hand, int finger, int link)
 
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)
 
geometry_msgs::Transform im_utils::Pose2Transform (const geometry_msgs::Pose pose_msg)
 
geometry_msgs::Pose im_utils::Transform2Pose (const geometry_msgs::Transform tf_msg)
 
geometry_msgs::Pose im_utils::UrdfPose2Pose (const urdf::Pose pose)
 


jsk_interactive_marker
Author(s): furuta
autogenerated on Sat Mar 20 2021 03:03:33