#include <chassis_base.h>

Public Member Functions | |
| ChassisBase ()=default | |
| bool | init (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) override |
| Get and check params for covariances. Setup odometry realtime publisher + odom message constant fields. init odom tf. More... | |
| void | update (const ros::Time &time, const ros::Duration &period) override |
| Receive real_time command from manual. Execute different action according to current mode. Set necessary params of chassis. Execute power limit. More... | |
Public Member Functions inherited from controller_interface::MultiInterfaceController< T... > | |
| virtual bool | init (hardware_interface::RobotHW *, ros::NodeHandle &) |
| MultiInterfaceController (bool allow_optional_interfaces=false) | |
Public Member Functions inherited from controller_interface::ControllerBase | |
| virtual void | aborting (const ros::Time &) |
| virtual void | aborting (const ros::Time &) |
| bool | abortRequest (const ros::Time &time) |
| bool | abortRequest (const ros::Time &time) |
| ControllerBase ()=default | |
| ControllerBase (const ControllerBase &)=delete | |
| ControllerBase (ControllerBase &&)=delete | |
| bool | isAborted () const |
| bool | isAborted () const |
| bool | isInitialized () const |
| bool | isInitialized () const |
| bool | isRunning () const |
| bool | isRunning () const |
| bool | isStopped () const |
| bool | isStopped () const |
| bool | isWaiting () const |
| bool | isWaiting () const |
| ControllerBase & | operator= (const ControllerBase &)=delete |
| ControllerBase & | operator= (ControllerBase &&)=delete |
| 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) |
| void | updateRequest (const ros::Time &time, const ros::Duration &period) |
| void | updateRequest (const ros::Time &time, const ros::Duration &period) |
| virtual void | waiting (const ros::Time &) |
| virtual void | waiting (const ros::Time &) |
| bool | waitRequest (const ros::Time &time) |
| bool | waitRequest (const ros::Time &time) |
| virtual | ~ControllerBase ()=default |
Protected Types | |
| enum | { RAW, FOLLOW, TWIST } |
Protected Member Functions | |
| 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... | |
| virtual void | moveJoint (const ros::Time &time, const ros::Duration &period)=0 |
| virtual geometry_msgs::Twist | odometry ()=0 |
| 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... | |
Protected Member Functions inherited from controller_interface::MultiInterfaceController< T... > | |
| bool | initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) override |
Additional Inherited Members | |
Public Types inherited from controller_interface::ControllerBase | |
| typedef std::vector< hardware_interface::InterfaceResources > | ClaimedResources |
| enum | ControllerState { ControllerState::CONSTRUCTED, ControllerState::INITIALIZED, ControllerState::RUNNING, ControllerState::STOPPED, ControllerState::WAITING, ControllerState::ABORTED } |
Public Attributes inherited from controller_interface::ControllerBase | |
| ControllerState | state_ |
Static Protected Member Functions inherited from controller_interface::MultiInterfaceController< T... > | |
| 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) |
Definition at line 92 of file chassis_base.h.
|
protected |
| Enumerator | |
|---|---|
| RAW | |
| FOLLOW | |
| TWIST | |
Definition at line 187 of file chassis_base.h.
|
default |
|
protected |
Write current command from rm_msgs::ChassisCmd.
| msg | This message contains various state parameter settings for basic chassis control |
Definition at line 451 of file chassis_base.cpp.
|
protected |
Write current command from geometry_msgs::Twist.
| msg | This expresses velocity in free space broken into its linear and angular parts. |
Definition at line 458 of file chassis_base.cpp.
|
protected |
The mode FOLLOW: chassis will follow gimbal.
The mode FOLLOW: The chassis's direct will follow gimbal's direct all the time.
| time | The current time. |
| period | The time passed since the last call to update. |
Definition at line 213 of file chassis_base.cpp.
|
overridevirtual |
Get and check params for covariances. Setup odometry realtime publisher + odom message constant fields. init odom tf.
| robot_hw | The robot hardware abstraction. |
| root_nh | A NodeHandle in the root of the controller manager namespace. This is where the ROS interfaces are setup (publishers, subscribers, services). |
| controller_nh | A NodeHandle in the namespace of the controller. This is where the controller-specific configuration resides. |
Reimplemented from controller_interface::MultiInterfaceController< T... >.
Definition at line 83 of file chassis_base.cpp.
|
protectedpure virtual |
|
protectedpure virtual |
|
protected |
Definition at line 466 of file chassis_base.cpp.
|
protected |
To limit the chassis power according to current power limit.
Receive power limit from command. Set max_effort command to chassis to avoid exceed power limit.
Definition at line 410 of file chassis_base.cpp.
|
protected |
@briefThe The mode RAW: original state.
The mode raw: original state. Linear velocity will be set zero to stop move.
Definition at line 281 of file chassis_base.cpp.
|
protected |
Set chassis velocity to zero.
Definition at line 402 of file chassis_base.cpp.
|
protected |
Transform tf velocity to base link frame.
| from | The father frame. |
Definition at line 438 of file chassis_base.cpp.
|
protected |
The mode TWIST: Just moving chassis.
The mode TWIST: Chassis will move independent and will not effect by gimbal's move.
| time | The current time. |
| period | The time passed since the last call to update. |
Definition at line 241 of file chassis_base.cpp.
|
overridevirtual |
Receive real_time command from manual. Execute different action according to current mode. Set necessary params of chassis. Execute power limit.
Receive real_time command from manual and check whether it is normally, if can not receive command from manual for a while, chassis's velocity will be set zero to avoid out of control. Execute different action according to current mode such as RAW, FOLLOW, TWIST.(Their specific usage will be explain in the next). UpdateOdom,Set necessary params such as Acc and vel_tfed. Execute moving action and powerlimit.
| time | The current time. |
| period | The time passed since the last call to update. |
Implements controller_interface::ControllerBase.
Definition at line 152 of file chassis_base.cpp.
|
protected |
Init frame on base_link. Integral vel to pos and angle.
| time | The current time. |
| period | The time passed since the last call to update. |
Definition at line 294 of file chassis_base.cpp.
|
protected |
Definition at line 206 of file chassis_base.h.
|
protected |
Definition at line 209 of file chassis_base.h.
|
protected |
Definition at line 208 of file chassis_base.h.
|
protected |
Definition at line 207 of file chassis_base.h.
|
protected |
Definition at line 195 of file chassis_base.h.
|
protected |
Definition at line 180 of file chassis_base.h.
|
protected |
Definition at line 177 of file chassis_base.h.
|
protected |
Definition at line 183 of file chassis_base.h.
|
protected |
Definition at line 195 of file chassis_base.h.
|
protected |
Definition at line 178 of file chassis_base.h.
|
protected |
Definition at line 197 of file chassis_base.h.
|
protected |
Definition at line 182 of file chassis_base.h.
|
protected |
Definition at line 198 of file chassis_base.h.
|
protected |
Definition at line 210 of file chassis_base.h.
|
protected |
Definition at line 203 of file chassis_base.h.
|
protected |
Definition at line 205 of file chassis_base.h.
|
protected |
Definition at line 201 of file chassis_base.h.
|
protected |
Definition at line 181 of file chassis_base.h.
|
protected |
Definition at line 185 of file chassis_base.h.
|
protected |
Definition at line 180 of file chassis_base.h.
|
protected |
Definition at line 194 of file chassis_base.h.
|
protected |
Definition at line 194 of file chassis_base.h.
|
protected |
Definition at line 194 of file chassis_base.h.
|
protected |
Definition at line 176 of file chassis_base.h.
|
protected |
Definition at line 193 of file chassis_base.h.
|
protected |
Definition at line 186 of file chassis_base.h.
|
protected |
Definition at line 204 of file chassis_base.h.
|
protected |
Definition at line 180 of file chassis_base.h.
|
protected |
Definition at line 184 of file chassis_base.h.
|
protected |
Definition at line 180 of file chassis_base.h.
|
protected |
Definition at line 200 of file chassis_base.h.
|
protected |
Definition at line 180 of file chassis_base.h.
|
protected |
Definition at line 180 of file chassis_base.h.
|
protected |
Definition at line 199 of file chassis_base.h.