1 #ifndef WRENCHSTAMPED_VISUAL_H 2 #define WRENCHSTAMPED_VISUAL_H 4 #include <geometry_msgs/Wrench.h> 31 WrenchVisual( Ogre::SceneManager* scene_manager, Ogre::SceneNode* parent_node );
37 void setWrench(
const Ogre::Vector3 &force,
const Ogre::Vector3 &torque );
39 void setWrench(
const geometry_msgs::Wrench& wrench );
46 void setFramePosition(
const Ogre::Vector3& position );
47 void setFrameOrientation(
const Ogre::Quaternion& orientation );
51 void setForceColor(
float r,
float g,
float b,
float a );
52 void setTorqueColor(
float r,
float g,
float b,
float a );
53 void setForceScale(
float s );
54 void setTorqueScale(
float s );
55 void setWidth(
float w );
56 void setVisible(
bool visible );
64 float force_scale_, torque_scale_,
width_;
81 #endif // WRENCHSTAMPED_VISUAL_H rviz::BillboardLine * circle_torque_
rviz::Arrow * circle_arrow_torque_
Ogre::SceneManager * scene_manager_
Ogre::SceneNode * frame_node_
An object that displays a multi-segment line strip rendered as billboards.
Ogre::SceneNode * force_node_
Ogre::SceneNode * torque_node_
TFSIMD_FORCE_INLINE Vector3()
TFSIMD_FORCE_INLINE const tfScalar & w() const
rviz::Arrow * arrow_torque_
rviz::Arrow * arrow_force_
An arrow consisting of a cylinder and a cone.