|
| typedef std::vector< hardware_interface::InterfaceResources > | ClaimedResources |
| |
| void | updateState () |
| |
| virtual bool | init (hardware_interface::RobotHW *, ros::NodeHandle &) |
| |
| virtual bool | init (hardware_interface::RobotHW *, ros::NodeHandle &, ros::NodeHandle &) |
| |
| | MultiInterfaceController (bool allow_optional_interfaces=false) |
| |
| virtual | ~MultiInterfaceController () |
| |
| | ControllerBase () |
| |
| bool | isRunning () |
| |
| bool | isRunning () |
| |
| virtual void | starting (const ros::Time &) |
| |
| virtual void | starting (const ros::Time &) |
| |
| bool | startRequest (const ros::Time &time) |
| |
| bool | startRequest (const ros::Time &time) |
| |
| virtual void | stopping (const ros::Time &) |
| |
| virtual void | stopping (const ros::Time &) |
| |
| bool | stopRequest (const ros::Time &time) |
| |
| bool | stopRequest (const ros::Time &time) |
| |
| virtual void | update (const ros::Time &time, const ros::Duration &period)=0 |
| |
| virtual void | update (const ros::Time &time, const ros::Duration &period)=0 |
| |
| void | updateRequest (const ros::Time &time, const ros::Duration &period) |
| |
| void | updateRequest (const ros::Time &time, const ros::Duration &period) |
| |
| virtual | ~ControllerBase () |
| |
| | CONSTRUCTED |
| |
| | INITIALIZED |
| |
| | RUNNING |
| |
| enum controller_interface::ControllerBase:: { ... } | state_ |
| |
| bool | setup (const std::vector< typename UndercarriageDirectCtrl::WheelParams > &wheel_params) |
| |
| virtual bool | initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) |
| |
| static void | clearClaims (hardware_interface::RobotHW *robot_hw) |
| |
| static void | extractInterfaceResources (hardware_interface::RobotHW *robot_hw_in, hardware_interface::RobotHW *robot_hw_out) |
| |
| static bool | hasRequiredInterfaces (hardware_interface::RobotHW *robot_hw) |
| |
| static void | populateClaimedResources (hardware_interface::RobotHW *robot_hw, ClaimedResources &claimed_resources) |
| |
| std::vector< hardware_interface::JointHandle > | drive_joints_ |
| |
| boost::scoped_ptr< UndercarriageDirectCtrl > | geom_ |
| |
| std::vector< hardware_interface::JointHandle > | steer_joints_ |
| |
| std::vector< WheelState > | wheel_states_ |
| |
| bool | allow_optional_interfaces_ |
| |
| hardware_interface::RobotHW | robot_hw_ctrl_ |
| |
Definition at line 9 of file control_multi_plugin.cpp.