Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
rm_chassis_controllers::ChassisBase< T > Class Template Referenceabstract

#include <chassis_base.h>

Inheritance diagram for rm_chassis_controllers::ChassisBase< T >:
Inheritance graph
[legend]

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
 
ControllerBaseoperator= (const ControllerBase &)=delete
 
ControllerBaseoperator= (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
 

Protected Attributes

ros::Subscriber cmd_chassis_sub_
 
realtime_tools::RealtimeBuffer< Commandcmd_rt_buffer_
 
Command cmd_struct_
 
ros::Subscriber cmd_vel_sub_
 
std::string command_source_frame_ {}
 
double effort_coeff_ {}
 
hardware_interface::EffortJointInterfaceeffort_joint_interface_ {}
 
bool enable_odom_tf_ = false
 
std::string follow_source_frame_ {}
 
std::vector< hardware_interface::JointHandlejoint_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_ = false
 
double publish_rate_ {}
 
RampFilter< double > * ramp_w_ {}
 
RampFilter< double > * ramp_x_ {}
 
RampFilter< double > * ramp_y_ {}
 
rm_control::RobotStateHandle robot_state_handle_ {}
 
int state_ = RAW
 
bool state_changed_ = true
 
rm_common::TfRtBroadcaster tf_broadcaster_ {}
 
double timeout_ {}
 
bool topic_update_ = false
 
double twist_angular_ {}
 
geometry_msgs::Vector3 vel_cmd_ {}
 
double velocity_coeff_ {}
 
double wheel_radius_ {}
 
tf2::Transform world2odom_
 
- Protected Attributes inherited from controller_interface::MultiInterfaceController< T... >
bool allow_optional_interfaces_
 
hardware_interface::RobotHW robot_hw_ctrl_
 

Additional Inherited Members

- Public Types inherited from controller_interface::ControllerBase
typedef std::vector< hardware_interface::InterfaceResourcesClaimedResources
 
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)
 

Detailed Description

template<typename... T>
class rm_chassis_controllers::ChassisBase< T >

Definition at line 92 of file chassis_base.h.

Member Enumeration Documentation

◆ anonymous enum

template<typename... T>
anonymous enum
protected
Enumerator
RAW 
FOLLOW 
TWIST 

Definition at line 187 of file chassis_base.h.

Constructor & Destructor Documentation

◆ ChassisBase()

template<typename... T>
rm_chassis_controllers::ChassisBase< T >::ChassisBase ( )
default

Member Function Documentation

◆ cmdChassisCallback()

template<typename... T>
void rm_chassis_controllers::ChassisBase< T >::cmdChassisCallback ( const rm_msgs::ChassisCmdConstPtr &  msg)
protected

Write current command from rm_msgs::ChassisCmd.

Parameters
msgThis message contains various state parameter settings for basic chassis control

Definition at line 451 of file chassis_base.cpp.

◆ cmdVelCallback()

template<typename... T>
void rm_chassis_controllers::ChassisBase< T >::cmdVelCallback ( const geometry_msgs::Twist::ConstPtr &  msg)
protected

Write current command from geometry_msgs::Twist.

Parameters
msgThis expresses velocity in free space broken into its linear and angular parts.

Definition at line 458 of file chassis_base.cpp.

◆ follow()

template<typename... T>
void rm_chassis_controllers::ChassisBase< T >::follow ( const ros::Time time,
const ros::Duration period 
)
protected

The mode FOLLOW: chassis will follow gimbal.

The mode FOLLOW: The chassis's direct will follow gimbal's direct all the time.

Parameters
timeThe current time.
periodThe time passed since the last call to update.

Definition at line 213 of file chassis_base.cpp.

◆ init()

template<typename... T>
bool rm_chassis_controllers::ChassisBase< T >::init ( hardware_interface::RobotHW robot_hw,
ros::NodeHandle root_nh,
ros::NodeHandle controller_nh 
)
overridevirtual

Get and check params for covariances. Setup odometry realtime publisher + odom message constant fields. init odom tf.

Parameters
robot_hwThe robot hardware abstraction.
root_nhA NodeHandle in the root of the controller manager namespace. This is where the ROS interfaces are setup (publishers, subscribers, services).
controller_nhA NodeHandle in the namespace of the controller. This is where the controller-specific configuration resides.
Returns
True if initialization was successful and the controller is ready to be started.

Reimplemented from controller_interface::MultiInterfaceController< T... >.

Definition at line 83 of file chassis_base.cpp.

◆ moveJoint()

template<typename... T>
virtual void rm_chassis_controllers::ChassisBase< T >::moveJoint ( const ros::Time time,
const ros::Duration period 
)
protectedpure virtual

◆ odometry()

template<typename... T>
virtual geometry_msgs::Twist rm_chassis_controllers::ChassisBase< T >::odometry ( )
protectedpure virtual

◆ outsideOdomCallback()

template<typename... T>
void rm_chassis_controllers::ChassisBase< T >::outsideOdomCallback ( const nav_msgs::Odometry::ConstPtr &  msg)
protected

Definition at line 466 of file chassis_base.cpp.

◆ powerLimit()

template<typename... T>
void rm_chassis_controllers::ChassisBase< T >::powerLimit
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.

◆ raw()

template<typename... T>
void rm_chassis_controllers::ChassisBase< T >::raw
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.

◆ recovery()

template<typename... T>
void rm_chassis_controllers::ChassisBase< T >::recovery
protected

Set chassis velocity to zero.

Definition at line 402 of file chassis_base.cpp.

◆ tfVelToBase()

template<typename... T>
void rm_chassis_controllers::ChassisBase< T >::tfVelToBase ( const std::string &  from)
protected

Transform tf velocity to base link frame.

Parameters
fromThe father frame.

Definition at line 438 of file chassis_base.cpp.

◆ twist()

template<typename... T>
void rm_chassis_controllers::ChassisBase< T >::twist ( const ros::Time time,
const ros::Duration period 
)
protected

The mode TWIST: Just moving chassis.

The mode TWIST: Chassis will move independent and will not effect by gimbal's move.

Parameters
timeThe current time.
periodThe time passed since the last call to update.

Definition at line 241 of file chassis_base.cpp.

◆ update()

template<typename... T>
void rm_chassis_controllers::ChassisBase< T >::update ( const ros::Time time,
const ros::Duration period 
)
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.

Parameters
timeThe current time.
periodThe time passed since the last call to update.

Implements controller_interface::ControllerBase.

Definition at line 152 of file chassis_base.cpp.

◆ updateOdom()

template<typename... T>
void rm_chassis_controllers::ChassisBase< T >::updateOdom ( const ros::Time time,
const ros::Duration period 
)
protected

Init frame on base_link. Integral vel to pos and angle.

Parameters
timeThe current time.
periodThe time passed since the last call to update.

Definition at line 294 of file chassis_base.cpp.

Member Data Documentation

◆ cmd_chassis_sub_

template<typename... T>
ros::Subscriber rm_chassis_controllers::ChassisBase< T >::cmd_chassis_sub_
protected

Definition at line 206 of file chassis_base.h.

◆ cmd_rt_buffer_

template<typename... T>
realtime_tools::RealtimeBuffer<Command> rm_chassis_controllers::ChassisBase< T >::cmd_rt_buffer_
protected

Definition at line 209 of file chassis_base.h.

◆ cmd_struct_

template<typename... T>
Command rm_chassis_controllers::ChassisBase< T >::cmd_struct_
protected

Definition at line 208 of file chassis_base.h.

◆ cmd_vel_sub_

template<typename... T>
ros::Subscriber rm_chassis_controllers::ChassisBase< T >::cmd_vel_sub_
protected

Definition at line 207 of file chassis_base.h.

◆ command_source_frame_

template<typename... T>
std::string rm_chassis_controllers::ChassisBase< T >::command_source_frame_ {}
protected

Definition at line 195 of file chassis_base.h.

◆ effort_coeff_

template<typename... T>
double rm_chassis_controllers::ChassisBase< T >::effort_coeff_ {}
protected

Definition at line 180 of file chassis_base.h.

◆ effort_joint_interface_

template<typename... T>
hardware_interface::EffortJointInterface* rm_chassis_controllers::ChassisBase< T >::effort_joint_interface_ {}
protected

Definition at line 177 of file chassis_base.h.

◆ enable_odom_tf_

template<typename... T>
bool rm_chassis_controllers::ChassisBase< T >::enable_odom_tf_ = false
protected

Definition at line 183 of file chassis_base.h.

◆ follow_source_frame_

template<typename... T>
std::string rm_chassis_controllers::ChassisBase< T >::follow_source_frame_ {}
protected

Definition at line 195 of file chassis_base.h.

◆ joint_handles_

template<typename... T>
std::vector<hardware_interface::JointHandle> rm_chassis_controllers::ChassisBase< T >::joint_handles_ {}
protected

Definition at line 178 of file chassis_base.h.

◆ last_publish_time_

template<typename... T>
ros::Time rm_chassis_controllers::ChassisBase< T >::last_publish_time_
protected

Definition at line 197 of file chassis_base.h.

◆ max_odom_vel_

template<typename... T>
double rm_chassis_controllers::ChassisBase< T >::max_odom_vel_
protected

Definition at line 182 of file chassis_base.h.

◆ odom2base_

template<typename... T>
geometry_msgs::TransformStamped rm_chassis_controllers::ChassisBase< T >::odom2base_ {}
protected

Definition at line 198 of file chassis_base.h.

◆ odom_buffer_

template<typename... T>
realtime_tools::RealtimeBuffer<nav_msgs::Odometry> rm_chassis_controllers::ChassisBase< T >::odom_buffer_
protected

Definition at line 210 of file chassis_base.h.

◆ odom_pub_

template<typename... T>
std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::Odometry> > rm_chassis_controllers::ChassisBase< T >::odom_pub_
protected

Definition at line 203 of file chassis_base.h.

◆ outside_odom_sub_

template<typename... T>
ros::Subscriber rm_chassis_controllers::ChassisBase< T >::outside_odom_sub_
protected

Definition at line 205 of file chassis_base.h.

◆ pid_follow_

template<typename... T>
control_toolbox::Pid rm_chassis_controllers::ChassisBase< T >::pid_follow_
protected

Definition at line 201 of file chassis_base.h.

◆ power_offset_

template<typename... T>
double rm_chassis_controllers::ChassisBase< T >::power_offset_ {}
protected

Definition at line 181 of file chassis_base.h.

◆ publish_odom_tf_

template<typename... T>
bool rm_chassis_controllers::ChassisBase< T >::publish_odom_tf_ = false
protected

Definition at line 185 of file chassis_base.h.

◆ publish_rate_

template<typename... T>
double rm_chassis_controllers::ChassisBase< T >::publish_rate_ {}
protected

Definition at line 180 of file chassis_base.h.

◆ ramp_w_

template<typename... T>
RampFilter<double> * rm_chassis_controllers::ChassisBase< T >::ramp_w_ {}
protected

Definition at line 194 of file chassis_base.h.

◆ ramp_x_

template<typename... T>
RampFilter<double>* rm_chassis_controllers::ChassisBase< T >::ramp_x_ {}
protected

Definition at line 194 of file chassis_base.h.

◆ ramp_y_

template<typename... T>
RampFilter<double> * rm_chassis_controllers::ChassisBase< T >::ramp_y_ {}
protected

Definition at line 194 of file chassis_base.h.

◆ robot_state_handle_

template<typename... T>
rm_control::RobotStateHandle rm_chassis_controllers::ChassisBase< T >::robot_state_handle_ {}
protected

Definition at line 176 of file chassis_base.h.

◆ state_

template<typename... T>
int rm_chassis_controllers::ChassisBase< T >::state_ = RAW
protected

Definition at line 193 of file chassis_base.h.

◆ state_changed_

template<typename... T>
bool rm_chassis_controllers::ChassisBase< T >::state_changed_ = true
protected

Definition at line 186 of file chassis_base.h.

◆ tf_broadcaster_

template<typename... T>
rm_common::TfRtBroadcaster rm_chassis_controllers::ChassisBase< T >::tf_broadcaster_ {}
protected

Definition at line 204 of file chassis_base.h.

◆ timeout_

template<typename... T>
double rm_chassis_controllers::ChassisBase< T >::timeout_ {}
protected

Definition at line 180 of file chassis_base.h.

◆ topic_update_

template<typename... T>
bool rm_chassis_controllers::ChassisBase< T >::topic_update_ = false
protected

Definition at line 184 of file chassis_base.h.

◆ twist_angular_

template<typename... T>
double rm_chassis_controllers::ChassisBase< T >::twist_angular_ {}
protected

Definition at line 180 of file chassis_base.h.

◆ vel_cmd_

template<typename... T>
geometry_msgs::Vector3 rm_chassis_controllers::ChassisBase< T >::vel_cmd_ {}
protected

Definition at line 200 of file chassis_base.h.

◆ velocity_coeff_

template<typename... T>
double rm_chassis_controllers::ChassisBase< T >::velocity_coeff_ {}
protected

Definition at line 180 of file chassis_base.h.

◆ wheel_radius_

template<typename... T>
double rm_chassis_controllers::ChassisBase< T >::wheel_radius_ {}
protected

Definition at line 180 of file chassis_base.h.

◆ world2odom_

template<typename... T>
tf2::Transform rm_chassis_controllers::ChassisBase< T >::world2odom_
protected

Definition at line 199 of file chassis_base.h.


The documentation for this class was generated from the following files:


rm_chassis_controllers
Author(s): Qiayuan Liao
autogenerated on Sun May 4 2025 02:57:17