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 or . 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 or 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< ControlMethod > | 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. 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 or . More... | |
| double | gravity = 0 |
The currently acting gravity force or torque acting on this joint in or . 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 or . 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 or . 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 or . 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() |
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.
|
default |
|
default |
|
delete |
| double franka_gazebo::Joint::getDesiredAcceleration | ( | const franka::RobotMode & | mode | ) | const |
Decide what the desired acceleration of this joint is based on:
accelerationacceleration | [in] | mode | - the current mode the robot is in |
acceleration or 0 | double franka_gazebo::Joint::getDesiredPosition | ( | const franka::RobotMode & | mode | ) | const |
Decide what the desired position of this joint is based on:
positiondesired_positiondesired_positionposition | [in] | mode | - the current mode the robot is in |
position or desired_position | double franka_gazebo::Joint::getDesiredTorque | ( | const franka::RobotMode & | mode | ) | const |
| double franka_gazebo::Joint::getDesiredVelocity | ( | const franka::RobotMode & | mode | ) | const |
Decide what the desired velocity of this joint is based on:
velocityvelocitydesired_velocity | [in] | mode | - the current mode the robot is in |
velocity or desired_velocity | double franka_gazebo::Joint::getLinkMass | ( | ) | const |
| bool franka_gazebo::Joint::isInCollision | ( | ) | const |
Is the joint currently in contact with something?
true if effort > collision_threshold | bool franka_gazebo::Joint::isInContact | ( | ) | const |
Is the joint currently in contact with something?
true if effort > contact_threshold | void franka_gazebo::Joint::update | ( | const ros::Duration & | dt | ) |
| double franka_gazebo::Joint::acceleration = 0 |
| Eigen::Vector3d franka_gazebo::Joint::axis |
| double franka_gazebo::Joint::collision_threshold = std::numeric_limits<double>::infinity() |
Above which threshold forces or torques will be interpreted as "collisions" by isInCollision.
| double franka_gazebo::Joint::command = 0 |
| double franka_gazebo::Joint::contact_threshold = std::numeric_limits<double>::infinity() |
Above which threshold forces or torques will be interpreted as "contacts" by isInContact.
| boost::optional<ControlMethod> franka_gazebo::Joint::control_method = boost::none |
| 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.
| double franka_gazebo::Joint::desired_velocity = 0 |
| double franka_gazebo::Joint::effort = 0 |
| double franka_gazebo::Joint::gravity = 0 |
| gazebo::physics::JointPtr franka_gazebo::Joint::handle |
| double franka_gazebo::Joint::jerk = 0 |
|
private |
|
private |
| joint_limits_interface::JointLimits franka_gazebo::Joint::limits |
Joint limits.
| std::string franka_gazebo::Joint::name |
| double franka_gazebo::Joint::position = 0 |
| control_toolbox::Pid franka_gazebo::Joint::position_controller |
| double franka_gazebo::Joint::stop_position = 0 |
| int franka_gazebo::Joint::type |
The type of joint, i.e.
revolute, prismatic, ...
| double franka_gazebo::Joint::velocity = 0 |
| control_toolbox::Pid franka_gazebo::Joint::velocity_controller |