Skip to content

FarolGimmicks

FarolGimmicks namespace. More...

Functions

Name
template <typename T >
T
getParameters(ros::NodeHandle & _nh, std::string const & parameter_name)
Get the Parameters object.
template <typename T >
T
getParameters(ros::NodeHandle & _nh, std::string const & parameter_name, T default_value)
Get the Parameters object.
template <typename T >
T
getParameters(ros::NodeHandle & _nh, std::string const & parameter_name, T default_value, bool delete_param)
Get the Parameters object.
void spherical_to_cartesian(double bearing, double elevation, double range, double * out_pos_cart)
Convert from spherical to cartesian coordinates. Used mainly with usbl fixes.
int signVal(double v)
Returns the sign of a double.
double wrap2pi(double theta, const int mode)
Wraps angle between [0, 2PI] or [-PI, PI].
double wrapTo2pi(double in)
Wrap angle between [0, 2PI].
double angleDiff(double a, double b)
Method to calculate the diference between angles correctly even if they wrap between -pi and pi.
template <typename A ,typename B >
void
publishValue(ros::Publisher & pub, B & value)

Attributes

Name
const double PI
PI value.

Detailed Description

FarolGimmicks namespace.

Note: why the code of templates is here -> because linkage problems see https://stackoverflow.com/a/1353981

Functions Documentation

function getParameters

template <typename T >
T getParameters(
    ros::NodeHandle & _nh,
    std::string const & parameter_name
)

Get the Parameters object.

Parameters:

  • _nh ros nodehandle
  • parameter_name string with paramenter name

Template Parameters:

  • T the type of data of a desired parameter

Return: T parameter value

Note: Option not considering default value, so the config file must have the parameter;

function getParameters

template <typename T >
T getParameters(
    ros::NodeHandle & _nh,
    std::string const & parameter_name,
    T default_value
)

Get the Parameters object.

Parameters:

  • _nh ros nodehandle
  • parameter_name string with parameter name
  • default_value default value of the parameter

Template Parameters:

  • T the type of data of a desired parameter

Return: T parameter value

Note: Option considering default value. Even if the parameter doesn't exist in config file it is possible to use a default value.

function getParameters

template <typename T >
T getParameters(
    ros::NodeHandle & _nh,
    std::string const & parameter_name,
    T default_value,
    bool delete_param
)

Get the Parameters object.

Parameters:

  • _nh ros nodehandle
  • parameter_name string with parameter name
  • default_value default value of the parameter
  • delete_param boolean to delete or not the parameter from parameter server

Template Parameters:

  • T the type of data of a desired parameter

Return: T parameter value

Note: Option considering default value. Even if the parameter doesn't exist in config file it is possible to use a default value. Removes parameter from parameter server

function spherical_to_cartesian

void spherical_to_cartesian(
    double bearing,
    double elevation,
    double range,
    double * out_pos_cart
)

Convert from spherical to cartesian coordinates. Used mainly with usbl fixes.

Parameters:

  • bearing horizontal angle between the direction of an object and another object or between it and the true north direction in degrees.
  • elevation angle measured between the horizontal and the vehicle line of sight to the object
  • range distance to the object
  • out_pos_cart cartesian coordinates pointer

function signVal

int signVal(
    double v
)

Returns the sign of a double.

Parameters:

  • v double value

Return:

  • int 1 if value is positive
  • int 0 if value is 0
  • int -1 if value is negative

function wrap2pi

double wrap2pi(
    double theta,
    const int mode
)

Wraps angle between [0, 2PI] or [-PI, PI].

Parameters:

  • theta angle in radians
  • mode 0 = Wrap from [0, 2*pi]; 1 = Wrap from [-pi, pi]

Return: double wraped angle

function wrapTo2pi

double wrapTo2pi(
    double in
)

Wrap angle between [0, 2PI].

Parameters:

  • in angle in radians

Return: double wraped angle

function angleDiff

double angleDiff(
    double a,
    double b
)

Method to calculate the diference between angles correctly even if they wrap between -pi and pi.

Parameters:

  • a angle 1 in radians
  • b angle 2 in radians

Return: double

function publishValue

template <typename A ,
typename B >
void publishValue(
    ros::Publisher & pub,
    B & value
)

Parameters:

  • pub publisher
  • value value

Template Parameters:

  • A value type
  • B publisher type

Attributes Documentation

variable PI

const double PI = 3.14159265;

PI value.


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


Last update: March 7, 2024