Skip to content

RosController

ROS implementation of the innerloops controllers. Based on a desired reference computes the force or torque to be applied.

#include <ros_controller.h>

Public Functions

Name
RosController(ros::NodeHandle & nh, std::string controller_name, std::string refCallback_topic, double * state, double * force_or_torque, double frequency)
Constructor of a innerloop controller.
RosController(ros::NodeHandle & nh, std::string controller_name, std::string refCallback_topic, double * state, double * state_dot, double * force_or_torque, double frequency)
Constructor of a innerloop controller.
RosController(ros::NodeHandle & nh, std::string controller_name, std::string refCallback_topic, double * state, double * force_or_torque, double frequency, bool * turn_limiter_flag, double * turn_radius_speed, RateLimiter * rate_limiter, double * turn_radius_speed_t)
Constructor of a innerloop yaw controller.
RosController(ros::NodeHandle & nh, std::string controller_name, std::string refCallback_topic, double * state, double * force_or_torque, double frequency, bool * turn_limiter_flag, double * turn_radius_speed, double * turn_radius_speed_t)
Constructor of a innerloop yaw_rate controller.
virtual double computeCommand()
Core function. Computes the PID output.
void setCircularUnits(const bool & flag)
Setter function for the circular units flag.
void setPositiveOutput(const bool & flag)
Set the Positive Output object.
std::string getControllerName() const
Get the Controller Name object.
void setFFGainsPID(const float & kff, const float & kff_d, const float & kff_lin_drag, const float kff_quad_drag)
Set the Feedforwar gains P I D object.
void setGainsPID(const float & kp, const float & ki, const float & kd)
Set the Gains P I D object.
void setLimitBoundsPID(const float & max_out, const float & min_out)

Protected Functions

Name
void refCallback(const std_msgs::Float64 & ptr)
Callback function. Saturates the value if boundaries exist.
void init(ros::NodeHandle & nh, std::string controller_name, std::string refCallback_topic)
Initialize function. Reads the parameters, creates a pid controller if any gain is different from zero and subscribes to the relevant topic.
virtual bool validRef()
Check if the reference is new.

Protected Attributes

Name
ros::Duration timeout_ref_
std::string controller_name_
double ref_value_
double max_ref_value_
double min_ref_value_
ros::Time ref_time_
ros::Time last_cmd_
bool debug_
farol_msgs::mPidDebug debug_msg_
double * state_ptr_
double * force_or_torque_ptr_
double frequency_
bool * turn_limiter_flag_ptr_
double min_turn_radius_
bool turn_limit_yaw_ref_
bool turn_limit_yaw_rate_ref_
double * turn_radius_speed_
double * turn_radius_speed_t_
double turn_radius_speed_t_max_
RateLimiter * rate_limiter_ptr_
bool circular_units_
bool positive_output_
PID_Controller * pid_c_
ros::Subscriber ros_sub_
ros::Publisher debug_pub_

Public Functions Documentation

function RosController

RosController(
    ros::NodeHandle & nh,
    std::string controller_name,
    std::string refCallback_topic,
    double * state,
    double * force_or_torque,
    double frequency
)

Constructor of a innerloop controller.

Parameters:

  • nh ROS nodehandle to read parameters and subscribe to relevant topics
  • controller_name Controller name (variable being controlled)
  • refCallback_topic Topic name
  • state Pointer to state variable being controlled
  • force_or_torque Pointer to force or torque output
  • frequency Frequency of controller sampling rate

function RosController

RosController(
    ros::NodeHandle & nh,
    std::string controller_name,
    std::string refCallback_topic,
    double * state,
    double * state_dot,
    double * force_or_torque,
    double frequency
)

Constructor of a innerloop controller.

Parameters:

  • nh ROS nodehandle to read parameters and subscribe to relevant topics
  • controller_name Controller name (variable being controlled)
  • refCallback_topic Topic name
  • state Pointer to state variable being controlled
  • state_dot Pointer to the derivative of the state variable being controlled
  • force_or_torque Pointer to force or torque output
  • frequency Frequency of controller sampling rate

function RosController

RosController(
    ros::NodeHandle & nh,
    std::string controller_name,
    std::string refCallback_topic,
    double * state,
    double * force_or_torque,
    double frequency,
    bool * turn_limiter_flag,
    double * turn_radius_speed,
    RateLimiter * rate_limiter,
    double * turn_radius_speed_t
)

Constructor of a innerloop yaw controller.

Parameters:

  • nh ROS nodehandle to read parameters and subscribe to relevant topics
  • controller_name Controller name (variable being controlled)
  • refCallback_topic Topic name
  • state Pointer to state variable being controlled
  • force_or_torque Pointer to force or torque output
  • frequency Frequency of controller sampling rate
  • turn_limiter_flag On/off flag for turning radius limiter
  • surge Surge speed of vehicle
  • rate_limiter Rate Limiter object from dsor_utils

function RosController

RosController(
    ros::NodeHandle & nh,
    std::string controller_name,
    std::string refCallback_topic,
    double * state,
    double * force_or_torque,
    double frequency,
    bool * turn_limiter_flag,
    double * turn_radius_speed,
    double * turn_radius_speed_t
)

Constructor of a innerloop yaw_rate controller.

Parameters:

  • nh ROS nodehandle to read parameters and subscribe to relevant topics
  • controller_name Controller name (variable being controlled)
  • refCallback_topic Topic name
  • state Pointer to state variable being controlled
  • force_or_torque Pointer to force or torque output
  • frequency Frequency of controller sampling rate
  • turn_limiter_flag On/off flag for turning radius limiter
  • surge Surge speed of vehicle

function computeCommand

virtual double computeCommand()

Core function. Computes the PID output.

Return: The force or torque that result from the PID computation

function setCircularUnits

inline void setCircularUnits(
    const bool & flag
)

Setter function for the circular units flag.

Parameters:

  • flag true for controllers using angles, false otherwise

function setPositiveOutput

inline void setPositiveOutput(
    const bool & flag
)

Set the Positive Output object.

Parameters:

  • flag

function getControllerName

inline std::string getControllerName() const

Get the Controller Name object.

function setFFGainsPID

inline void setFFGainsPID(
    const float & kff,
    const float & kff_d,
    const float & kff_lin_drag,
    const float kff_quad_drag
)

Set the Feedforwar gains P I D object.

Parameters:

  • kff Feedforward gain (quadratic)
  • kff_d Feedforwad derivative gain
  • kff_lin_drag Feedforward linear drag gain
  • kff_quad_drag Feedforwad quadratic drag gain

function setGainsPID

inline void setGainsPID(
    const float & kp,
    const float & ki,
    const float & kd
)

Set the Gains P I D object.

Parameters:

  • kp Proportional gain
  • ki Integral gain
  • kd Derivative gain

function setLimitBoundsPID

inline void setLimitBoundsPID(
    const float & max_out,
    const float & min_out
)

Protected Functions Documentation

function refCallback

void refCallback(
    const std_msgs::Float64 & ptr
)

Callback function. Saturates the value if boundaries exist.

Parameters:

  • msg Float64 value of the variable being controlled

function init

void init(
    ros::NodeHandle & nh,
    std::string controller_name,
    std::string refCallback_topic
)

Initialize function. Reads the parameters, creates a pid controller if any gain is different from zero and subscribes to the relevant topic.

Parameters:

  • nh Nodehandle to read parameters and subscribe to relevant topics
  • controller_name Controller name (variable being controlled)
  • refCallback_topic Topic name

function validRef

virtual bool validRef()

Check if the reference is new.

Return: True if valid, false otherwise

Protected Attributes Documentation

variable timeout_ref_

ros::Duration timeout_ref_;

variable controller_name_

std::string controller_name_;

variable ref_value_

double ref_value_;

variable max_ref_value_

double max_ref_value_;

variable min_ref_value_

double min_ref_value_;

variable ref_time_

ros::Time ref_time_;

variable last_cmd_

ros::Time last_cmd_;

variable debug_

bool debug_;

variable debug_msg_

farol_msgs::mPidDebug debug_msg_;

variable state_ptr_

double * state_ptr_;

variable force_or_torque_ptr_

double * force_or_torque_ptr_;

variable frequency_

double frequency_;

variable turn_limiter_flag_ptr_

bool * turn_limiter_flag_ptr_;

variable min_turn_radius_

double min_turn_radius_;

variable turn_limit_yaw_ref_

bool turn_limit_yaw_ref_ {false};

variable turn_limit_yaw_rate_ref_

bool turn_limit_yaw_rate_ref_ {false};

variable turn_radius_speed_

double * turn_radius_speed_;

variable turn_radius_speed_t_

double * turn_radius_speed_t_;

variable turn_radius_speed_t_max_

double turn_radius_speed_t_max_;

variable rate_limiter_ptr_

RateLimiter * rate_limiter_ptr_;

variable circular_units_

bool circular_units_;

variable positive_output_

bool positive_output_;

variable pid_c_

PID_Controller * pid_c_;

variable ros_sub_

ros::Subscriber ros_sub_;

variable debug_pub_

ros::Publisher debug_pub_;

Updated on 2024-03-07 at 10:30:48 +0000


Last update: March 7, 2024