Class TricycleController

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

  • public controller_interface::ControllerInterface

Class Documentation

class TricycleController : public controller_interface::ControllerInterface

Public Functions

TRICYCLE_CONTROLLER_PUBLIC TricycleController()
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 (const rclcpp::Time &time, const rclcpp::Duration &period) override
TRICYCLE_CONTROLLER_PUBLIC CallbackReturn on_init () 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

Protected 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<TractionHandle> traction_joint_
std::vector<SteeringHandle> steering_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_ = nullptr
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_
bool is_halted = false
bool use_stamped_vel_ = true
struct OdometryParams

Public Members

bool open_loop = false
bool enable_odom_tf = false
bool odom_only_twist = false
std::string base_frame_id = "base_link"
std::string odom_frame_id = "odom"
std::array<double, 6> pose_covariance_diagonal
std::array<double, 6> twist_covariance_diagonal
struct SteeringHandle

Public Members

std::reference_wrapper<const hardware_interface::LoanedStateInterface> position_state
std::reference_wrapper<hardware_interface::LoanedCommandInterface> position_command
struct TractionHandle

Public Members

std::reference_wrapper<const hardware_interface::LoanedStateInterface> velocity_state
std::reference_wrapper<hardware_interface::LoanedCommandInterface> velocity_command
struct WheelParams

Public Members

double wheelbase = 0.0
double radius = 0.0