1 #ifndef WRENCHSTAMPED_VISUAL_H 2 #define WRENCHSTAMPED_VISUAL_H 4 #include <geometry_msgs/Wrench.h> 29 WrenchVisual(Ogre::SceneManager* scene_manager, Ogre::SceneNode* parent_node);
35 void setWrench(
const Ogre::Vector3& force,
const Ogre::Vector3& torque);
37 void setWrench(
const geometry_msgs::Wrench& wrench);
44 void setFramePosition(
const Ogre::Vector3& position);
45 void setFrameOrientation(
const Ogre::Quaternion& orientation);
49 void setForceColor(
float r,
float g,
float b,
float a);
50 void setTorqueColor(
float r,
float g,
float b,
float a);
51 void setForceScale(
float s);
52 void setTorqueScale(
float s);
53 void setWidth(
float w);
54 void setHideSmallValues(
bool h);
63 float force_scale_, torque_scale_,
width_;
80 #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_
void setVisible(PanelDockWidget *widget, bool visible)
Ogre::SceneNode * torque_node_
rviz::Arrow * arrow_torque_
rviz::Arrow * arrow_force_
An arrow consisting of a cylinder and a cone.