ros2_control - foxy
Loading...
Searching...
No Matches
Classes | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
tricycle_controller::TricycleController Class Reference
Inheritance diagram for tricycle_controller::TricycleController:
Inheritance graph
[legend]
Collaboration diagram for tricycle_controller::TricycleController:
Collaboration graph
[legend]

Classes

struct  OdometryParams
 
struct  SteeringHandle
 
struct  TractionHandle
 
struct  WheelParams
 

Public Member Functions

TRICYCLE_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration () const override
 
TRICYCLE_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration () const override
 
TRICYCLE_CONTROLLER_PUBLIC controller_interface::return_type update () override
 
TRICYCLE_CONTROLLER_PUBLIC controller_interface::return_type init (const std::string &controller_name) override
 
TRICYCLE_CONTROLLER_PUBLIC CallbackReturn on_configure (const rclcpp_lifecycle::State &previous_state) override
 
TRICYCLE_CONTROLLER_PUBLIC CallbackReturn on_activate (const rclcpp_lifecycle::State &previous_state) override
 
TRICYCLE_CONTROLLER_PUBLIC CallbackReturn on_deactivate (const rclcpp_lifecycle::State &previous_state) override
 
TRICYCLE_CONTROLLER_PUBLIC CallbackReturn on_cleanup (const rclcpp_lifecycle::State &previous_state) override
 
TRICYCLE_CONTROLLER_PUBLIC CallbackReturn on_error (const rclcpp_lifecycle::State &previous_state) override
 
TRICYCLE_CONTROLLER_PUBLIC CallbackReturn on_shutdown (const rclcpp_lifecycle::State &previous_state) override
 
- Public Member Functions inherited from controller_interface::ControllerInterface
CONTROLLER_INTERFACE_PUBLIC void assign_interfaces (std::vector< hardware_interface::LoanedCommandInterface > &&command_interfaces, std::vector< hardware_interface::LoanedStateInterface > &&state_interfaces)
 
CONTROLLER_INTERFACE_PUBLIC void release_interfaces ()
 
virtual CONTROLLER_INTERFACE_PUBLIC return_type init (const std::string &controller_name, rclcpp::NodeOptions &node_options)
 
CONTROLLER_INTERFACE_PUBLIC std::shared_ptr< rclcpp::Node > get_node ()
 
template<typename ParameterT >
auto auto_declare (const std::string &name, const ParameterT &default_value)
 Declare and initialize a parameter with a type.
 
CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & configure ()
 
CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & cleanup ()
 
CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & deactivate ()
 
CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & activate ()
 
CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & shutdown ()
 
CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & get_current_state () const
 

Protected Member Functions

CallbackReturn get_traction (const std::string &traction_joint_name, std::vector< TractionHandle > &joint)
 
CallbackReturn get_steering (const std::string &steering_joint_name, std::vector< SteeringHandle > &joint)
 
double convert_trans_rot_vel_to_steering_angle (double v, double omega, double wheelbase)
 
std::tuple< double, double > twist_to_ackermann (double linear_command, double angular_command)
 
void reset_odometry (const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< std_srvs::srv::Empty::Request > req, std::shared_ptr< std_srvs::srv::Empty::Response > res)
 
bool reset ()
 
void halt ()
 

Protected Attributes

std::string traction_joint_name_
 
std::string steering_joint_name_
 
std::vector< TractionHandletraction_joint_
 
std::vector< SteeringHandlesteering_joint_
 
struct tricycle_controller::TricycleController::WheelParams wheel_params_
 
struct tricycle_controller::TricycleController::OdometryParams odom_params_
 
bool publish_ackermann_command_ = false
 
std::shared_ptr< rclcpp::Publisher< AckermannDrive > > ackermann_command_publisher_ = nullptr
 
std::shared_ptr< realtime_tools::RealtimePublisher< AckermannDrive > > realtime_ackermann_command_publisher_ = nullptr
 
Odometry odometry_
 
std::shared_ptr< rclcpp::Publisher< nav_msgs::msg::Odometry > > odometry_publisher_ = nullptr
 
std::shared_ptr< realtime_tools::RealtimePublisher< nav_msgs::msg::Odometry > > realtime_odometry_publisher_ = nullptr
 
std::shared_ptr< rclcpp::Publisher< tf2_msgs::msg::TFMessage > > odometry_transform_publisher_
 
std::shared_ptr< realtime_tools::RealtimePublisher< tf2_msgs::msg::TFMessage > > realtime_odometry_transform_publisher_ = nullptr
 
std::chrono::milliseconds cmd_vel_timeout_ {500}
 
bool subscriber_is_active_ = false
 
rclcpp::Subscription< TwistStamped >::SharedPtr velocity_command_subscriber_ = nullptr
 
rclcpp::Subscription< geometry_msgs::msg::Twist >::SharedPtr velocity_command_unstamped_subscriber_ = nullptr
 
realtime_tools::RealtimeBox< std::shared_ptr< TwistStamped > > received_velocity_msg_ptr_ {nullptr}
 
rclcpp::Service< std_srvs::srv::Empty >::SharedPtr reset_odom_service_
 
std::queue< AckermannDrive > previous_commands_
 
TractionLimiter limiter_traction_
 
SteeringLimiter limiter_steering_
 
rclcpp::Time previous_update_timestamp_ {0}
 
double publish_rate_ = 50.0
 
rclcpp::Duration publish_period_ {0, 0}
 
rclcpp::Time previous_publish_timestamp_ {0}
 
bool is_halted = false
 
bool use_stamped_vel_ = true
 
- Protected Attributes inherited from controller_interface::ControllerInterface
std::vector< hardware_interface::LoanedCommandInterfacecommand_interfaces_
 
std::vector< hardware_interface::LoanedStateInterfacestate_interfaces_
 
std::shared_ptr< rclcpp::Node > node_
 
rclcpp_lifecycle::State lifecycle_state_
 

Member Function Documentation

◆ command_interface_configuration()

InterfaceConfiguration tricycle_controller::TricycleController::command_interface_configuration ( ) const
overridevirtual

◆ init()

controller_interface::return_type tricycle_controller::TricycleController::init ( const std::string &  controller_name)
overridevirtual

◆ state_interface_configuration()

InterfaceConfiguration tricycle_controller::TricycleController::state_interface_configuration ( ) const
overridevirtual

◆ update()

controller_interface::return_type tricycle_controller::TricycleController::update ( )
overridevirtual

Member Data Documentation

◆ odometry_transform_publisher_

std::shared_ptr<rclcpp::Publisher<tf2_msgs::msg::TFMessage> > tricycle_controller::TricycleController::odometry_transform_publisher_
protected
Initial value:
=
nullptr

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