#include <head_plugin.h>
| Public Member Functions | |
| void | Load (physics::ModelPtr _model, sdf::ElementPtr _sdf) | 
| void | OnUpdate (const common::UpdateInfo &) | 
| Private Member Functions | |
| void | head_cmd_callback (const drc_plugin::DRC_HEAD_CMD::ConstPtr &cmd) | 
| void | moveJoint () | 
| void | scan_callback (const sensor_msgs::LaserScanPtr &scan) | 
| void | setMoveJoint (float target, long msTime, int mode) | 
| Private Attributes | |
| tf::TransformBroadcaster | broadcaster | 
| sensor_msgs::PointCloud2 | cloud | 
| int | cloud_accum_cnt | 
| ros::Publisher | cloud_pub | 
| ros::Subscriber | cmd_sub | 
| sdf::ElementPtr | element | 
| physics::JointController * | JCon | 
| ros::Publisher | joint_pub | 
| sensor_msgs::JointState | joint_state | 
| JOINT_DATA | jointData | 
| physics::JointPtr | JPtr_Hokuyo | 
| physics::ModelPtr | model | 
| double | ref_Hokuyo | 
| ros::Subscriber | scan_sub | 
| SCAN_DATA | scanData | 
| tf::Transform | toCamera | 
| tf::Transform | toHokuyo | 
| tf::Transform | toStreaming | 
| event::ConnectionPtr | UpdateConnection | 
Definition at line 65 of file head_plugin.h.
| void gazebo::HeadPlugin::head_cmd_callback | ( | const drc_plugin::DRC_HEAD_CMD::ConstPtr & | cmd | ) |  [private] | 
Definition at line 101 of file head_plugin.cpp.
| void gazebo::HeadPlugin::Load | ( | physics::ModelPtr | _model, | 
| sdf::ElementPtr | _sdf | ||
| ) | 
Definition at line 14 of file head_plugin.cpp.
| void gazebo::HeadPlugin::moveJoint | ( | ) |  [private] | 
Definition at line 162 of file head_plugin.cpp.
| void gazebo::HeadPlugin::OnUpdate | ( | const common::UpdateInfo & | ) | 
Definition at line 116 of file head_plugin.cpp.
| void gazebo::HeadPlugin::scan_callback | ( | const sensor_msgs::LaserScanPtr & | scan | ) |  [private] | 
Definition at line 79 of file head_plugin.cpp.
| void gazebo::HeadPlugin::setMoveJoint | ( | float | target, | 
| long | msTime, | ||
| int | mode | ||
| ) |  [private] | 
Definition at line 151 of file head_plugin.cpp.
Definition at line 80 of file head_plugin.h.
| sensor_msgs::PointCloud2 gazebo::HeadPlugin::cloud  [private] | 
Definition at line 85 of file head_plugin.h.
| int gazebo::HeadPlugin::cloud_accum_cnt  [private] | 
Definition at line 86 of file head_plugin.h.
| ros::Publisher gazebo::HeadPlugin::cloud_pub  [private] | 
Definition at line 75 of file head_plugin.h.
| ros::Subscriber gazebo::HeadPlugin::cmd_sub  [private] | 
Definition at line 76 of file head_plugin.h.
| sdf::ElementPtr gazebo::HeadPlugin::element  [private] | 
Definition at line 93 of file head_plugin.h.
| physics::JointController* gazebo::HeadPlugin::JCon  [private] | 
Definition at line 100 of file head_plugin.h.
| ros::Publisher gazebo::HeadPlugin::joint_pub  [private] | 
Definition at line 74 of file head_plugin.h.
| sensor_msgs::JointState gazebo::HeadPlugin::joint_state  [private] | 
Definition at line 79 of file head_plugin.h.
| JOINT_DATA gazebo::HeadPlugin::jointData  [private] | 
Definition at line 106 of file head_plugin.h.
| physics::JointPtr gazebo::HeadPlugin::JPtr_Hokuyo  [private] | 
Definition at line 101 of file head_plugin.h.
| physics::ModelPtr gazebo::HeadPlugin::model  [private] | 
Definition at line 92 of file head_plugin.h.
| double gazebo::HeadPlugin::ref_Hokuyo  [private] | 
Definition at line 104 of file head_plugin.h.
| ros::Subscriber gazebo::HeadPlugin::scan_sub  [private] | 
Definition at line 77 of file head_plugin.h.
| SCAN_DATA gazebo::HeadPlugin::scanData  [private] | 
Definition at line 107 of file head_plugin.h.
| tf::Transform gazebo::HeadPlugin::toCamera  [private] | 
Definition at line 82 of file head_plugin.h.
| tf::Transform gazebo::HeadPlugin::toHokuyo  [private] | 
Definition at line 81 of file head_plugin.h.
| tf::Transform gazebo::HeadPlugin::toStreaming  [private] | 
Definition at line 83 of file head_plugin.h.
Definition at line 96 of file head_plugin.h.