|
| typedef std::vector< hardware_interface::InterfaceResources > | ClaimedResources |
| |
| enum | ControllerState {
ControllerState::CONSTRUCTED,
ControllerState::INITIALIZED,
ControllerState::RUNNING,
ControllerState::STOPPED,
ControllerState::WAITING,
ControllerState::ABORTED
} |
| |
| ControllerState | state_ |
| |
| enum | |
| |
| void | cmdChassisCallback (const rm_msgs::ChassisCmdConstPtr &msg) |
| | Write current command from rm_msgs::ChassisCmd. More...
|
| |
| void | cmdVelCallback (const geometry_msgs::Twist::ConstPtr &msg) |
| | Write current command from geometry_msgs::Twist. More...
|
| |
| void | follow (const ros::Time &time, const ros::Duration &period) |
| | The mode FOLLOW: chassis will follow gimbal. More...
|
| |
| void | outsideOdomCallback (const nav_msgs::Odometry::ConstPtr &msg) |
| |
| void | powerLimit () |
| | To limit the chassis power according to current power limit. More...
|
| |
| void | raw () |
| |
| void | recovery () |
| | Set chassis velocity to zero. More...
|
| |
| void | tfVelToBase (const std::string &from) |
| | Transform tf velocity to base link frame. More...
|
| |
| void | twist (const ros::Time &time, const ros::Duration &period) |
| | The mode TWIST: Just moving chassis. More...
|
| |
| void | updateOdom (const ros::Time &time, const ros::Duration &period) |
| | Init frame on base_link. Integral vel to pos and angle. More...
|
| |
| bool | initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) override |
| |
| 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) |
| |
| ros::Subscriber | cmd_chassis_sub_ |
| |
| realtime_tools::RealtimeBuffer< Command > | cmd_rt_buffer_ |
| |
| Command | cmd_struct_ |
| |
| ros::Subscriber | cmd_vel_sub_ |
| |
| std::string | command_source_frame_ |
| |
| double | effort_coeff_ |
| |
| hardware_interface::EffortJointInterface * | effort_joint_interface_ |
| |
| bool | enable_odom_tf_ |
| |
| std::string | follow_source_frame_ |
| |
| std::vector< hardware_interface::JointHandle > | joint_handles_ |
| |
| ros::Time | last_publish_time_ |
| |
| double | max_odom_vel_ |
| |
| geometry_msgs::TransformStamped | odom2base_ |
| |
| realtime_tools::RealtimeBuffer< nav_msgs::Odometry > | odom_buffer_ |
| |
| std::shared_ptr< realtime_tools::RealtimePublisher< nav_msgs::Odometry > > | odom_pub_ |
| |
| ros::Subscriber | outside_odom_sub_ |
| |
| control_toolbox::Pid | pid_follow_ |
| |
| double | power_offset_ |
| |
| bool | publish_odom_tf_ |
| |
| double | publish_rate_ |
| |
| RampFilter< double > * | ramp_w_ |
| |
| RampFilter< double > * | ramp_x_ |
| |
| RampFilter< double > * | ramp_y_ |
| |
| rm_control::RobotStateHandle | robot_state_handle_ |
| |
| int | state_ |
| |
| bool | state_changed_ |
| |
| rm_common::TfRtBroadcaster | tf_broadcaster_ |
| |
| double | timeout_ |
| |
| bool | topic_update_ |
| |
| double | twist_angular_ |
| |
| geometry_msgs::Vector3 | vel_cmd_ |
| |
| double | velocity_coeff_ |
| |
| double | wheel_radius_ |
| |
| tf2::Transform | world2odom_ |
| |
| bool | allow_optional_interfaces_ |
| |
| hardware_interface::RobotHW | robot_hw_ctrl_ |
| |
Definition at line 86 of file swerve.h.