joint.cpp
Go to the documentation of this file.
1 #include <franka_gazebo/joint.h>
2 #include <urdf/model.h>
3 #include <gazebo/physics/Link.hh>
4 
5 namespace franka_gazebo {
6 
7 void Joint::update(const ros::Duration& dt) {
8  if (not this->handle) {
9  return;
10  }
11 
12  this->velocity = this->handle->GetVelocity(0);
13 #if GAZEBO_MAJOR_VERSION >= 8
14  double position = this->handle->Position(0);
15 #else
16  double position = this->handle->GetAngle(0).Radian();
17 #endif
18  ignition::math::Vector3d f;
19  switch (this->type) {
20  case urdf::Joint::PRISMATIC:
21  this->position = position;
22 #if GAZEBO_MAJOR_VERSION >= 8
23  f = this->handle->GetForceTorque(0).body2Force;
24 #else
25  f = this->handle->GetForceTorque(0).body2Force.Ign();
26 #endif
27  break;
28  case urdf::Joint::REVOLUTE:
29  case urdf::Joint::CONTINUOUS:
30  this->position += angles::shortest_angular_distance(this->position, position);
31 #if GAZEBO_MAJOR_VERSION >= 8
32  f = this->handle->GetForceTorque(0).body2Torque;
33 #else
34  f = this->handle->GetForceTorque(0).body2Torque.Ign();
35 #endif
36  break;
37  default:
38  throw std::logic_error("Unknown joint type: " + std::to_string(this->type));
39  }
40  this->effort = Eigen::Vector3d(f.X(), f.Y(), f.Z()).dot(this->axis);
41 
42  if (std::isnan(this->lastVelocity)) {
43  this->lastVelocity = this->velocity;
44  }
45  this->acceleration = (this->velocity - this->lastVelocity) / dt.toSec();
46  this->lastVelocity = this->velocity;
47 
48  if (std::isnan(this->lastAcceleration)) {
49  this->lastAcceleration = this->acceleration;
50  }
51  this->jerk = (this->acceleration - this->lastAcceleration) / dt.toSec();
52  this->lastAcceleration = this->acceleration;
53 }
54 
55 double Joint::getDesiredPosition(const franka::RobotMode& mode) const {
56  if (mode != franka::RobotMode::kMove) {
57  return this->position;
58  }
61  return this->desired_position;
62  }
63  return this->position;
64 }
65 
66 double Joint::getDesiredVelocity(const franka::RobotMode& mode) const {
67  if (mode != franka::RobotMode::kMove) {
68  return this->velocity;
69  }
71  return this->velocity;
72  }
73  return this->desired_velocity;
74 }
75 
77  if (mode != franka::RobotMode::kMove) {
78  return this->acceleration;
79  }
81  return 0;
82  }
83  return this->acceleration;
84 }
85 
86 double Joint::getDesiredTorque(const franka::RobotMode& mode) const {
87  if (mode != franka::RobotMode::kMove) {
88  return 0;
89  }
91  return 0;
92  }
93  return command;
94 }
95 
96 double Joint::getLinkMass() const {
97  if (not this->handle) {
98  return std::numeric_limits<double>::quiet_NaN();
99  }
100 #if GAZEBO_MAJOR_VERSION >= 8
101  return this->handle->GetChild()->GetInertial()->Mass();
102 #else
103  return this->handle->GetChild()->GetInertial()->GetMass();
104 #endif
105 }
106 
107 bool Joint::isInCollision() const {
108  return std::abs(this->effort - this->command) > this->collision_threshold;
109 }
110 
111 bool Joint::isInContact() const {
112  return std::abs(this->effort - this->command) > this->contact_threshold;
113 }
114 } // namespace franka_gazebo
double getDesiredPosition(const franka::RobotMode &mode) const
Decide what the desired position of this joint is based on:
Definition: joint.cpp:55
int type
The type of joint, i.e.
Definition: joint.h:45
double lastAcceleration
Definition: joint.h:172
double collision_threshold
Above which threshold forces or torques will be interpreted as "collisions" by isInCollision.
Definition: joint.h:98
double getDesiredTorque(const franka::RobotMode &mode) const
Decide what the desired torque of this joint is:
Definition: joint.cpp:86
void update(const ros::Duration &dt)
Calculate all members such as accelerations, jerks velocities by differentiation. ...
Definition: joint.cpp:7
double desired_position
The current desired position that is used for the PID controller when the joints control method is "P...
Definition: joint.h:62
f
double contact_threshold
Above which threshold forces or torques will be interpreted as "contacts" by isInContact.
Definition: joint.h:94
double jerk
The currently acting jerk acting on this this joint in either or .
Definition: joint.h:87
double velocity
The current velocity of this joint either in or .
Definition: joint.h:80
double acceleration
The currently acting acceleration on this joint in either or .
Definition: joint.h:91
gazebo::physics::JointPtr handle
A pointer to the underlying gazebo handle. Must be non-null for update to work.
Definition: joint.h:41
bool isInCollision() const
Is the joint currently in contact with something?
Definition: joint.cpp:107
doubleAcc dot(const VectorAcc &lhs, const VectorAcc &rhs)
double getLinkMass() const
Get the total link mass of this joint&#39;s child.
Definition: joint.cpp:96
bool isInContact() const
Is the joint currently in contact with something?
Definition: joint.cpp:111
double effort
The current total force or torque acting on this joint in either or .
Definition: joint.h:83
Eigen::Vector3d axis
The axis of rotation/translation of this joint in local coordinates.
Definition: joint.h:52
double getDesiredVelocity(const franka::RobotMode &mode) const
Decide what the desired velocity of this joint is based on:
Definition: joint.cpp:66
double getDesiredAcceleration(const franka::RobotMode &mode) const
Decide what the desired acceleration of this joint is based on:
Definition: joint.cpp:76
double position
The current position of this joint either in or .
Definition: joint.h:77
double command
The currently applied command from a controller acting on this joint either in or without gravity...
Definition: joint.h:56
double lastVelocity
Definition: joint.h:171
double desired_velocity
The current desired velocity that is used for the PID controller when the joints control method is "V...
Definition: joint.h:67
boost::optional< ControlMethod > control_method
Decides whether the joint is doing torque control or if the position or velocity should be controlled...
Definition: joint.h:71
def shortest_angular_distance(from_angle, to_angle)


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