Public Member Functions | Private Member Functions | Private Attributes | List of all members
rm_chassis_controllers::SentryController Class Reference

#include <sentry.h>

Inheritance diagram for rm_chassis_controllers::SentryController:
Inheritance graph
[legend]

Public Member Functions

bool init (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) override
 Execute ChassisBase::init. Init necessary handles. More...
 
 SentryController ()=default
 
- Public Member Functions inherited from rm_chassis_controllers::ChassisBase< rm_control::RobotStateInterface, hardware_interface::EffortJointInterface >
 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
 

Private Member Functions

void catapult (const ros::Time &time, const ros::Duration &period)
 
void moveJoint (const ros::Time &time, const ros::Duration &period) override
 Calculate correct command and set it to wheel. More...
 
void normal (const ros::Time &time, const ros::Duration &period)
 
geometry_msgs::Twist odometry () override
 Calculate current linear_x according to current velocity. More...
 

Private Attributes

double catapult_angle_
 
double catapult_initial_velocity_
 
effort_controllers::JointPositionController ctrl_catapult_joint_
 
effort_controllers::JointVelocityController ctrl_wheel_
 
bool if_catapult_
 
double last_vel_cmd_ { 0. }
 
double lock_duratoin_
 
ros::Time lock_time_
 
double vel_coff_
 

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_
 
- Protected Types inherited from rm_chassis_controllers::ChassisBase< rm_control::RobotStateInterface, hardware_interface::EffortJointInterface >
enum  
 
- Protected Member Functions inherited from rm_chassis_controllers::ChassisBase< rm_control::RobotStateInterface, hardware_interface::EffortJointInterface >
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...
 
- 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
 
- 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)
 
- Protected Attributes inherited from rm_chassis_controllers::ChassisBase< rm_control::RobotStateInterface, hardware_interface::EffortJointInterface >
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_
 
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_
 
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_
 
- Protected Attributes inherited from controller_interface::MultiInterfaceController< T... >
bool allow_optional_interfaces_
 
hardware_interface::RobotHW robot_hw_ctrl_
 

Detailed Description

Definition at line 76 of file sentry.h.

Constructor & Destructor Documentation

◆ SentryController()

rm_chassis_controllers::SentryController::SentryController ( )
default

Member Function Documentation

◆ catapult()

void rm_chassis_controllers::SentryController::catapult ( const ros::Time time,
const ros::Duration period 
)
private

Definition at line 119 of file sentry.cpp.

◆ init()

bool rm_chassis_controllers::SentryController::init ( hardware_interface::RobotHW robot_hw,
ros::NodeHandle root_nh,
ros::NodeHandle controller_nh 
)
overridevirtual

Execute ChassisBase::init. Init necessary handles.

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 75 of file sentry.cpp.

◆ moveJoint()

void rm_chassis_controllers::SentryController::moveJoint ( const ros::Time time,
const ros::Duration period 
)
overrideprivatevirtual

Calculate correct command and set it to wheel.

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

Implements rm_chassis_controllers::ChassisBase< rm_control::RobotStateInterface, hardware_interface::EffortJointInterface >.

Definition at line 95 of file sentry.cpp.

◆ normal()

void rm_chassis_controllers::SentryController::normal ( const ros::Time time,
const ros::Duration period 
)
private

Definition at line 146 of file sentry.cpp.

◆ odometry()

geometry_msgs::Twist rm_chassis_controllers::SentryController::odometry ( )
overrideprivatevirtual

Calculate current linear_x according to current velocity.

Returns
Calculated vel_data included linear_x.

Implements rm_chassis_controllers::ChassisBase< rm_control::RobotStateInterface, hardware_interface::EffortJointInterface >.

Definition at line 139 of file sentry.cpp.

Member Data Documentation

◆ catapult_angle_

double rm_chassis_controllers::SentryController::catapult_angle_
private

Definition at line 143 of file sentry.h.

◆ catapult_initial_velocity_

double rm_chassis_controllers::SentryController::catapult_initial_velocity_
private

Definition at line 142 of file sentry.h.

◆ ctrl_catapult_joint_

effort_controllers::JointPositionController rm_chassis_controllers::SentryController::ctrl_catapult_joint_
private

Definition at line 139 of file sentry.h.

◆ ctrl_wheel_

effort_controllers::JointVelocityController rm_chassis_controllers::SentryController::ctrl_wheel_
private

Definition at line 138 of file sentry.h.

◆ if_catapult_

bool rm_chassis_controllers::SentryController::if_catapult_
private

Definition at line 141 of file sentry.h.

◆ last_vel_cmd_

double rm_chassis_controllers::SentryController::last_vel_cmd_ { 0. }
private

Definition at line 145 of file sentry.h.

◆ lock_duratoin_

double rm_chassis_controllers::SentryController::lock_duratoin_
private

Definition at line 147 of file sentry.h.

◆ lock_time_

ros::Time rm_chassis_controllers::SentryController::lock_time_
private

Definition at line 146 of file sentry.h.

◆ vel_coff_

double rm_chassis_controllers::SentryController::vel_coff_
private

Definition at line 144 of file sentry.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