Public Member Functions | |
void | DeferredLoad () |
void | Load (physics::ModelPtr _parent, sdf::ElementPtr _sdf) |
void | OnUpdate (const common::UpdateInfo &) |
void | RosQueueThread () |
void | SetPoseCommand (const geometry_msgs::Pose::ConstPtr &_msg) |
void | SetVelCommand (const geometry_msgs::Twist::ConstPtr &_msg) |
Private Attributes | |
math::Vector3 | angular_vel |
bool | apply_in_gazebo_loop |
boost::thread | callbackQueeuThread |
boost::thread | deferredLoadThread |
math::Vector3 | linear_vel |
physics::LinkPtr | link |
std::string | link_name |
physics::ModelPtr | model |
std::string | obj_name |
math::Pose | pose |
ros::NodeHandle * | rosNode |
ros::CallbackQueue | rosQueue |
bool | set_pose_flag |
bool | set_vel_flag |
ros::Subscriber | subPoseCommand |
ros::Subscriber | subVelCommand |
event::ConnectionPtr | updateConnection |
Definition at line 23 of file SetVelPlugin.cpp.
void gazebo::SetVel::DeferredLoad | ( | ) | [inline] |
Definition at line 72 of file SetVelPlugin.cpp.
void gazebo::SetVel::Load | ( | physics::ModelPtr | _parent, |
sdf::ElementPtr | _sdf | ||
) | [inline] |
Definition at line 28 of file SetVelPlugin.cpp.
void gazebo::SetVel::OnUpdate | ( | const common::UpdateInfo & | ) | [inline] |
Definition at line 128 of file SetVelPlugin.cpp.
void gazebo::SetVel::RosQueueThread | ( | ) | [inline] |
Definition at line 142 of file SetVelPlugin.cpp.
void gazebo::SetVel::SetPoseCommand | ( | const geometry_msgs::Pose::ConstPtr & | _msg | ) | [inline] |
Definition at line 113 of file SetVelPlugin.cpp.
void gazebo::SetVel::SetVelCommand | ( | const geometry_msgs::Twist::ConstPtr & | _msg | ) | [inline] |
Definition at line 97 of file SetVelPlugin.cpp.
math::Vector3 gazebo::SetVel::angular_vel [private] |
Definition at line 155 of file SetVelPlugin.cpp.
bool gazebo::SetVel::apply_in_gazebo_loop [private] |
Definition at line 161 of file SetVelPlugin.cpp.
boost::thread gazebo::SetVel::callbackQueeuThread [private] |
Definition at line 167 of file SetVelPlugin.cpp.
boost::thread gazebo::SetVel::deferredLoadThread [private] |
Definition at line 168 of file SetVelPlugin.cpp.
math::Vector3 gazebo::SetVel::linear_vel [private] |
Definition at line 154 of file SetVelPlugin.cpp.
physics::LinkPtr gazebo::SetVel::link [private] |
Definition at line 157 of file SetVelPlugin.cpp.
std::string gazebo::SetVel::link_name [private] |
Definition at line 153 of file SetVelPlugin.cpp.
physics::ModelPtr gazebo::SetVel::model [private] |
Definition at line 151 of file SetVelPlugin.cpp.
std::string gazebo::SetVel::obj_name [private] |
Definition at line 152 of file SetVelPlugin.cpp.
math::Pose gazebo::SetVel::pose [private] |
Definition at line 156 of file SetVelPlugin.cpp.
ros::NodeHandle* gazebo::SetVel::rosNode [private] |
Definition at line 163 of file SetVelPlugin.cpp.
ros::CallbackQueue gazebo::SetVel::rosQueue [private] |
Definition at line 164 of file SetVelPlugin.cpp.
bool gazebo::SetVel::set_pose_flag [private] |
Definition at line 159 of file SetVelPlugin.cpp.
bool gazebo::SetVel::set_vel_flag [private] |
Definition at line 160 of file SetVelPlugin.cpp.
Definition at line 166 of file SetVelPlugin.cpp.
ros::Subscriber gazebo::SetVel::subVelCommand [private] |
Definition at line 165 of file SetVelPlugin.cpp.
Definition at line 158 of file SetVelPlugin.cpp.