1 #ifndef EFFORT_VISUAL_H 2 #define EFFORT_VISUAL_H 4 #include <sensor_msgs/JointState.h> 44 void setMessage(
const sensor_msgs::JointStateConstPtr& msg );
51 void setFramePosition(
const Ogre::Vector3& position );
52 void setFrameOrientation(
const Ogre::Quaternion& orientation );
55 void setFramePosition(
const std::string joint_name,
const Ogre::Vector3& position );
56 void setFrameOrientation(
const std::string joint_name,
const Ogre::Quaternion& orientation );
58 void setFrameEnabled(
const std::string joint_name,
const bool e );
62 void setColor(
float r,
float g,
float b,
float a );
64 void setWidth(
float w );
66 void setScale(
float s );
93 #endif // EFFORT_VISUAL_H std::map< std::string, Ogre::Quaternion > orientation_
std::map< std::string, rviz::Arrow * > effort_arrow_
Ogre::SceneNode * frame_node_
std::map< std::string, Ogre::Vector3 > position_
TFSIMD_FORCE_INLINE Vector3()
std::map< std::string, rviz::BillboardLine * > effort_circle_
Ogre::SceneManager * scene_manager_
std::map< std::string, bool > effort_enabled_
TFSIMD_FORCE_INLINE const tfScalar & w() const
boost::shared_ptr< urdf::Model > urdf_model_
static void getRainbowColor(float value, Ogre::ColourValue &color)