Public Member Functions | |
void | addForce () |
void | DeferredLoad () |
void | Load (physics::ModelPtr _parent, sdf::ElementPtr _sdf) |
void | OnUpdate (const common::UpdateInfo &) |
void | publishState () |
void | ServiceCallbackThread () |
bool | SetStateCallback (hrpsys_gazebo_msgs::LIPSetStateRequest &req, hrpsys_gazebo_msgs::LIPSetStateResponse &res) |
bool | SwitchFootCallback (hrpsys_gazebo_msgs::LIPSwitchFootRequest &req, hrpsys_gazebo_msgs::LIPSwitchFootResponse &res) |
Private Attributes | |
physics::LinkPtr | base_link_ |
boost::thread | deferred_load_thread_ |
physics::JointPtr | linear_joint_ |
physics::LinkPtr | mass_link_ |
physics::ModelPtr | model_ |
PubMultiQueue | pmq_ |
physics::JointPtr | root_x_joint_ |
physics::JointPtr | root_y_joint_ |
ros::NodeHandle * | ros_node_ |
boost::thread | service_callback_thread_ |
ros::CallbackQueue | service_queue_ |
ros::ServiceServer | set_state_srv_ |
ros::Publisher | state_pub_ |
PubQueue < hrpsys_gazebo_msgs::LIPState > ::Ptr | state_pub_queue_ |
ros::ServiceServer | switch_foot_srv_ |
event::ConnectionPtr | update_connection_ |
Definition at line 27 of file LIPPlugin.cpp.
void gazebo::LIPPlugin::addForce | ( | ) | [inline] |
Definition at line 174 of file LIPPlugin.cpp.
void gazebo::LIPPlugin::DeferredLoad | ( | ) | [inline] |
Definition at line 49 of file LIPPlugin.cpp.
void gazebo::LIPPlugin::Load | ( | physics::ModelPtr | _parent, |
sdf::ElementPtr | _sdf | ||
) | [inline] |
Definition at line 32 of file LIPPlugin.cpp.
void gazebo::LIPPlugin::OnUpdate | ( | const common::UpdateInfo & | ) | [inline] |
Definition at line 168 of file LIPPlugin.cpp.
void gazebo::LIPPlugin::publishState | ( | ) | [inline] |
Definition at line 191 of file LIPPlugin.cpp.
void gazebo::LIPPlugin::ServiceCallbackThread | ( | ) | [inline] |
Definition at line 109 of file LIPPlugin.cpp.
bool gazebo::LIPPlugin::SetStateCallback | ( | hrpsys_gazebo_msgs::LIPSetStateRequest & | req, |
hrpsys_gazebo_msgs::LIPSetStateResponse & | res | ||
) | [inline] |
Definition at line 143 of file LIPPlugin.cpp.
bool gazebo::LIPPlugin::SwitchFootCallback | ( | hrpsys_gazebo_msgs::LIPSwitchFootRequest & | req, |
hrpsys_gazebo_msgs::LIPSwitchFootResponse & | res | ||
) | [inline] |
Definition at line 115 of file LIPPlugin.cpp.
physics::LinkPtr gazebo::LIPPlugin::base_link_ [private] |
Definition at line 233 of file LIPPlugin.cpp.
boost::thread gazebo::LIPPlugin::deferred_load_thread_ [private] |
Definition at line 224 of file LIPPlugin.cpp.
physics::JointPtr gazebo::LIPPlugin::linear_joint_ [private] |
Definition at line 237 of file LIPPlugin.cpp.
physics::LinkPtr gazebo::LIPPlugin::mass_link_ [private] |
Definition at line 234 of file LIPPlugin.cpp.
physics::ModelPtr gazebo::LIPPlugin::model_ [private] |
Definition at line 218 of file LIPPlugin.cpp.
PubMultiQueue gazebo::LIPPlugin::pmq_ [private] |
Definition at line 222 of file LIPPlugin.cpp.
physics::JointPtr gazebo::LIPPlugin::root_x_joint_ [private] |
Definition at line 235 of file LIPPlugin.cpp.
physics::JointPtr gazebo::LIPPlugin::root_y_joint_ [private] |
Definition at line 236 of file LIPPlugin.cpp.
ros::NodeHandle* gazebo::LIPPlugin::ros_node_ [private] |
Definition at line 221 of file LIPPlugin.cpp.
boost::thread gazebo::LIPPlugin::service_callback_thread_ [private] |
Definition at line 225 of file LIPPlugin.cpp.
Definition at line 239 of file LIPPlugin.cpp.
Definition at line 231 of file LIPPlugin.cpp.
ros::Publisher gazebo::LIPPlugin::state_pub_ [private] |
Definition at line 227 of file LIPPlugin.cpp.
PubQueue<hrpsys_gazebo_msgs::LIPState>::Ptr gazebo::LIPPlugin::state_pub_queue_ [private] |
Definition at line 228 of file LIPPlugin.cpp.
Definition at line 230 of file LIPPlugin.cpp.
Definition at line 219 of file LIPPlugin.cpp.