3 #include <gazebo/physics/Link.hh> 12 this->
velocity = this->handle->GetVelocity(0);
13 #if GAZEBO_MAJOR_VERSION >= 8 14 double position = this->handle->Position(0);
16 double position = this->handle->GetAngle(0).Radian();
18 ignition::math::Vector3d
f;
20 case urdf::Joint::PRISMATIC:
22 #if GAZEBO_MAJOR_VERSION >= 8 23 f = this->handle->GetForceTorque(0).body2Force;
25 f = this->handle->GetForceTorque(0).body2Force.Ign();
28 case urdf::Joint::REVOLUTE:
29 case urdf::Joint::CONTINUOUS:
31 #if GAZEBO_MAJOR_VERSION >= 8 32 f = this->handle->GetForceTorque(0).body2Torque;
34 f = this->handle->GetForceTorque(0).body2Torque.Ign();
38 throw std::logic_error(
"Unknown joint type: " + std::to_string(this->
type));
40 this->
effort = Eigen::Vector3d(f.X(), f.Y(), f.Z()).
dot(this->
axis);
98 return std::numeric_limits<double>::quiet_NaN();
100 #if GAZEBO_MAJOR_VERSION >= 8 101 return this->handle->GetChild()->GetInertial()->Mass();
103 return this->handle->GetChild()->GetInertial()->GetMass();
double getDesiredPosition(const franka::RobotMode &mode) const
Decide what the desired position of this joint is based on:
int type
The type of joint, i.e.
double collision_threshold
Above which threshold forces or torques will be interpreted as "collisions" by isInCollision.
double getDesiredTorque(const franka::RobotMode &mode) const
Decide what the desired torque of this joint is:
void update(const ros::Duration &dt)
Calculate all members such as accelerations, jerks velocities by differentiation. ...
double desired_position
The current desired position that is used for the PID controller when the joints control method is "P...
double contact_threshold
Above which threshold forces or torques will be interpreted as "contacts" by isInContact.
double jerk
The currently acting jerk acting on this this joint in either or .
double velocity
The current velocity of this joint either in or .
double acceleration
The currently acting acceleration on this joint in either or .
gazebo::physics::JointPtr handle
A pointer to the underlying gazebo handle. Must be non-null for update to work.
bool isInCollision() const
Is the joint currently in contact with something?
doubleAcc dot(const VectorAcc &lhs, const VectorAcc &rhs)
double getLinkMass() const
Get the total link mass of this joint's child.
bool isInContact() const
Is the joint currently in contact with something?
double effort
The current total force or torque acting on this joint in either or .
Eigen::Vector3d axis
The axis of rotation/translation of this joint in local coordinates.
double getDesiredVelocity(const franka::RobotMode &mode) const
Decide what the desired velocity of this joint is based on:
double getDesiredAcceleration(const franka::RobotMode &mode) const
Decide what the desired acceleration of this joint is based on:
double position
The current position of this joint either in or .
double command
The currently applied command from a controller acting on this joint either in or without gravity...
double desired_velocity
The current desired velocity that is used for the PID controller when the joints control method is "V...
boost::optional< ControlMethod > control_method
Decides whether the joint is doing torque control or if the position or velocity should be controlled...
def shortest_angular_distance(from_angle, to_angle)