1 #include <OgreVector3.h> 2 #include <OgreSceneNode.h> 3 #include <OgreSceneManager.h> 34 for (std::map<std::string, urdf::JointSharedPtr >::iterator it =
urdf_model_->joints_.begin(); it !=
urdf_model_->joints_.end(); it ++ ) {
35 if ( it->second->type == urdf::Joint::REVOLUTE ) {
36 std::string joint_name = it->first;
59 value = std::min(value, 1.0
f);
60 value = std::max(value, 0.0
f);
62 float h = value * 5.0f + 1.0f;
65 if ( !(i&1) ) f = 1 - f;
68 if (i <= 1) color[0] = n, color[1] = 0, color[2] = 1;
69 else if (i == 2) color[0] = 0, color[1] = n, color[2] = 1;
70 else if (i == 3) color[0] = 0, color[1] = 1, color[2] = n;
71 else if (i == 4) color[0] = n, color[1] = 1, color[2] = 0;
72 else if (i >= 5) color[0] = 1, color[1] = n, color[2] = 0;
78 int joint_num = msg->name.size();
79 for (
int i = 0; i < joint_num; i++ )
81 std::string joint_name = msg->name[i];
82 double effort = msg->effort[i];
83 const urdf::Joint* joint =
urdf_model_->getJoint(joint_name).get();
84 int joint_type = joint->type;
85 if ( joint_type == urdf::Joint::REVOLUTE )
106 urdf::JointLimitsSharedPtr
limit = joint->limits;
107 double max_effort = limit->effort, effort_value = 0.05;
109 if ( max_effort != 0.0 )
111 effort_value = std::min(fabs(effort) / max_effort, 1.0) + 0.05;
113 effort_value = fabs(effort) + 0.05;
125 for (
int i = 0; i < 30; i++) {
126 Ogre::Vector3 point = Ogre::Vector3((0.05+effort_value*scale_*0.5)*sin(i*2*M_PI/32), (0.05+effort_value*scale_*0.5)*cos(i*2*M_PI/32), 0);
127 if ( effort < 0 ) point.x = -point.x;
130 Ogre::ColourValue color;
132 effort_arrow_[joint_name]->setColor(color.r, color.g, color.b, color.a);
133 effort_circle_[joint_name]->setColor(color.r, color.g, color.b, color.a);
std::map< std::string, Ogre::Quaternion > orientation_
void getRainbowColor(float value, Ogre::ColourValue &color)
void setMessage(const sensor_msgs::JointStateConstPtr &msg)
An object that displays a multi-segment line strip rendered as billboards.
void setFramePosition(const Ogre::Vector3 &position)
std::map< std::string, rviz::Arrow * > effort_arrow_
Ogre::SceneNode * frame_node_
std::map< std::string, Ogre::Vector3 > position_
std::map< std::string, rviz::BillboardLine * > effort_circle_
Ogre::SceneManager * scene_manager_
std::map< std::string, bool > effort_enabled_
EffortVisual(Ogre::SceneManager *scene_manager, Ogre::SceneNode *parent_node, boost::shared_ptr< urdf::Model > urdf_model)
void setFrameEnabled(const std::string joint_name, const bool e)
void setFrameOrientation(const Ogre::Quaternion &orientation)
An arrow consisting of a cylinder and a cone.
boost::shared_ptr< urdf::Model > urdf_model_