Public Member Functions | Public Attributes | Private Attributes | List of all members
franka_gazebo::Joint Struct Reference

A data container holding all relevant information about a robotic joint. More...

#include <joint.h>

Public Member Functions

double getDesiredAcceleration (const franka::RobotMode &mode) const
 Decide what the desired acceleration of this joint is based on: More...
 
double getDesiredPosition (const franka::RobotMode &mode) const
 Decide what the desired position of this joint is based on: More...
 
double getDesiredTorque (const franka::RobotMode &mode) const
 Decide what the desired torque of this joint is: More...
 
double getDesiredVelocity (const franka::RobotMode &mode) const
 Decide what the desired velocity of this joint is based on: More...
 
double getLinkMass () const
 Get the total link mass of this joint's child. More...
 
bool isInCollision () const
 Is the joint currently in contact with something? More...
 
bool isInContact () const
 Is the joint currently in contact with something? More...
 
 Joint ()=default
 
 Joint (Joint &&)=default
 
 Joint (const Joint &)=delete
 
void update (const ros::Duration &dt)
 Calculate all members such as accelerations, jerks velocities by differentiation. More...
 

Public Attributes

double acceleration = 0
 The currently acting acceleration on this joint in either $\frac{m}{s^2}$ or $\frac{rad}{s^2}$. More...
 
Eigen::Vector3d axis
 The axis of rotation/translation of this joint in local coordinates. More...
 
double collision_threshold = std::numeric_limits<double>::infinity()
 Above which threshold forces or torques will be interpreted as "collisions" by isInCollision. More...
 
double command = 0
 The currently applied command from a controller acting on this joint either in $N$ or $Nm$ without gravity. More...
 
double contact_threshold = std::numeric_limits<double>::infinity()
 Above which threshold forces or torques will be interpreted as "contacts" by isInContact. More...
 
boost::optional< ControlMethodcontrol_method = boost::none
 Decides whether the joint is doing torque control or if the position or velocity should be controlled, or if the joint is entirely uncontrolled. More...
 
double desired_position = 0
 The current desired position that is used for the PID controller when the joints control method is "POSITION". More...
 
double desired_velocity = 0
 The current desired velocity that is used for the PID controller when the joints control method is "VELOCITY". More...
 
double effort = 0
 The current total force or torque acting on this joint in either $N$ or $Nm$. More...
 
double gravity = 0
 The currently acting gravity force or torque acting on this joint in $N$ or $Nm$. More...
 
gazebo::physics::JointPtr handle
 A pointer to the underlying gazebo handle. Must be non-null for update to work. More...
 
double jerk = 0
 The currently acting jerk acting on this this joint in either $\frac{m}{s^3}$ or $\frac{rad}{s^3}$. More...
 
joint_limits_interface::JointLimits limits
 Joint limits. More...
 
std::string name
 Name of this joint. Should be unique in whole simulation. More...
 
double position = 0
 The current position of this joint either in $m$ or $rad$. More...
 
control_toolbox::Pid position_controller
 The PID gains used for the controller, when in "position" control mode. More...
 
double stop_position = 0
 Position used as desired position if control_method is none. More...
 
int type
 The type of joint, i.e. More...
 
double velocity = 0
 The current velocity of this joint either in $\frac{m}{s}$ or $\frac{rad}{s}$. More...
 
control_toolbox::Pid velocity_controller
 The PID gains used for the controller, when in "velocity" control mode. More...
 

Private Attributes

double lastAcceleration = std::numeric_limits<double>::quiet_NaN()
 
double lastVelocity = std::numeric_limits<double>::quiet_NaN()
 

Detailed Description

A data container holding all relevant information about a robotic joint.

Calling update on this object will compute its internal state based on the all currently supplied information such as position, efforts etc.

Definition at line 25 of file joint.h.

Constructor & Destructor Documentation

◆ Joint() [1/3]

franka_gazebo::Joint::Joint ( )
default

◆ Joint() [2/3]

franka_gazebo::Joint::Joint ( Joint &&  )
default

◆ Joint() [3/3]

franka_gazebo::Joint::Joint ( const Joint )
delete

Member Function Documentation

◆ getDesiredAcceleration()

double franka_gazebo::Joint::getDesiredAcceleration ( const franka::RobotMode mode) const

Decide what the desired acceleration of this joint is based on:

  1. If a reflex is present, return acceleration
  2. ...otherwise if the control method is EFFORT, return 0
  3. ...otherwise return acceleration
    Parameters
    [in]mode- the current mode the robot is in
    Returns
    either acceleration or 0

Definition at line 76 of file joint.cpp.

◆ getDesiredPosition()

double franka_gazebo::Joint::getDesiredPosition ( const franka::RobotMode mode) const

Decide what the desired position of this joint is based on:

  1. If a reflex is present, return position
  2. ...otherwise if the control method is POSITION, return desired_position
  3. ...otherwise if the control method is EFFORT return desired_position
  1. ...otherwise return position
    Parameters
    [in]mode- the current mode the robot is in
    Returns
    either position or desired_position

Definition at line 55 of file joint.cpp.

◆ getDesiredTorque()

double franka_gazebo::Joint::getDesiredTorque ( const franka::RobotMode mode) const

Decide what the desired torque of this joint is:

  1. If a reflex is present, return 0
  2. ... otherwise if the control method is not EFFORT return 0
  3. ... otherwise return command
    Parameters
    [in]mode- the current mode the robot is in
    Returns
    either command or zero

Definition at line 86 of file joint.cpp.

◆ getDesiredVelocity()

double franka_gazebo::Joint::getDesiredVelocity ( const franka::RobotMode mode) const

Decide what the desired velocity of this joint is based on:

  1. If a reflex is present, return velocity
  2. ...otherwise if the control method is not VELOCITY, return velocity
  3. ...otherwise return desired_velocity
    Parameters
    [in]mode- the current mode the robot is in
    Returns
    either velocity or desired_velocity

Definition at line 66 of file joint.cpp.

◆ getLinkMass()

double franka_gazebo::Joint::getLinkMass ( ) const

Get the total link mass of this joint's child.

Returns
the mass in $kg$

Definition at line 96 of file joint.cpp.

◆ isInCollision()

bool franka_gazebo::Joint::isInCollision ( ) const

Is the joint currently in contact with something?

Returns
true if effort > collision_threshold

Definition at line 107 of file joint.cpp.

◆ isInContact()

bool franka_gazebo::Joint::isInContact ( ) const

Is the joint currently in contact with something?

Returns
true if effort > contact_threshold

Definition at line 111 of file joint.cpp.

◆ update()

void franka_gazebo::Joint::update ( const ros::Duration dt)

Calculate all members such as accelerations, jerks velocities by differentiation.

Parameters
[in]dtthe current time step since last time this method was called

Definition at line 7 of file joint.cpp.

Member Data Documentation

◆ acceleration

double franka_gazebo::Joint::acceleration = 0

The currently acting acceleration on this joint in either $\frac{m}{s^2}$ or $\frac{rad}{s^2}$.

Definition at line 91 of file joint.h.

◆ axis

Eigen::Vector3d franka_gazebo::Joint::axis

The axis of rotation/translation of this joint in local coordinates.

Definition at line 52 of file joint.h.

◆ collision_threshold

double franka_gazebo::Joint::collision_threshold = std::numeric_limits<double>::infinity()

Above which threshold forces or torques will be interpreted as "collisions" by isInCollision.

Definition at line 98 of file joint.h.

◆ command

double franka_gazebo::Joint::command = 0

The currently applied command from a controller acting on this joint either in $N$ or $Nm$ without gravity.

Definition at line 56 of file joint.h.

◆ contact_threshold

double franka_gazebo::Joint::contact_threshold = std::numeric_limits<double>::infinity()

Above which threshold forces or torques will be interpreted as "contacts" by isInContact.

Definition at line 94 of file joint.h.

◆ control_method

boost::optional<ControlMethod> franka_gazebo::Joint::control_method = boost::none

Decides whether the joint is doing torque control or if the position or velocity should be controlled, or if the joint is entirely uncontrolled.

Definition at line 71 of file joint.h.

◆ desired_position

double franka_gazebo::Joint::desired_position = 0

The current desired position that is used for the PID controller when the joints control method is "POSITION".

When the control method is not "POSITION", this value will only be updated once at the start of the controller and stay the same until a new controller is started.

Definition at line 62 of file joint.h.

◆ desired_velocity

double franka_gazebo::Joint::desired_velocity = 0

The current desired velocity that is used for the PID controller when the joints control method is "VELOCITY".

When the control method is not "VELOCITY", this value will be set to zero.

Definition at line 67 of file joint.h.

◆ effort

double franka_gazebo::Joint::effort = 0

The current total force or torque acting on this joint in either $N$ or $Nm$.

Definition at line 83 of file joint.h.

◆ gravity

double franka_gazebo::Joint::gravity = 0

The currently acting gravity force or torque acting on this joint in $N$ or $Nm$.

Definition at line 74 of file joint.h.

◆ handle

gazebo::physics::JointPtr franka_gazebo::Joint::handle

A pointer to the underlying gazebo handle. Must be non-null for update to work.

Definition at line 41 of file joint.h.

◆ jerk

double franka_gazebo::Joint::jerk = 0

The currently acting jerk acting on this this joint in either $\frac{m}{s^3}$ or $\frac{rad}{s^3}$.

Definition at line 87 of file joint.h.

◆ lastAcceleration

double franka_gazebo::Joint::lastAcceleration = std::numeric_limits<double>::quiet_NaN()
private

Definition at line 172 of file joint.h.

◆ lastVelocity

double franka_gazebo::Joint::lastVelocity = std::numeric_limits<double>::quiet_NaN()
private

Definition at line 171 of file joint.h.

◆ limits

joint_limits_interface::JointLimits franka_gazebo::Joint::limits

◆ name

std::string franka_gazebo::Joint::name

Name of this joint. Should be unique in whole simulation.

Definition at line 38 of file joint.h.

◆ position

double franka_gazebo::Joint::position = 0

The current position of this joint either in $m$ or $rad$.

Definition at line 77 of file joint.h.

◆ position_controller

control_toolbox::Pid franka_gazebo::Joint::position_controller

The PID gains used for the controller, when in "position" control mode.

In other modes these gains are ignored.

Definition at line 164 of file joint.h.

◆ stop_position

double franka_gazebo::Joint::stop_position = 0

Position used as desired position if control_method is none.

Definition at line 101 of file joint.h.

◆ type

int franka_gazebo::Joint::type

The type of joint, i.e.

revolute, prismatic, ...

See also
http://docs.ros.org/en/diamondback/api/urdf/html/classurdf_1_1Joint.html

Definition at line 45 of file joint.h.

◆ velocity

double franka_gazebo::Joint::velocity = 0

The current velocity of this joint either in $\frac{m}{s}$ or $\frac{rad}{s}$.

Definition at line 80 of file joint.h.

◆ velocity_controller

control_toolbox::Pid franka_gazebo::Joint::velocity_controller

The PID gains used for the controller, when in "velocity" control mode.

In other modes these gains are ignored.

Definition at line 168 of file joint.h.


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


franka_gazebo
Author(s): Franka Emika GmbH
autogenerated on Mon Sep 19 2022 03:06:05