RobWorkProject  23.9.11-
Classes | Public Types | Public Member Functions | List of all members
RecursiveNewtonEuler Class Reference

The recursive Newton-Euler method is used for calculating inverse dynamics of a kinematic tree. More...

#include <RecursiveNewtonEuler.hpp>

Classes

struct  Motion
 Motion of a body defined as velocity and acceleration. More...
 

Public Types

typedef rw::core::Ptr< RecursiveNewtonEulerPtr
 smart pointer type to this class
 

Public Member Functions

 RecursiveNewtonEuler (rw::core::Ptr< rwsim::dynamics::RigidDevice > device)
 Constructor for inverse dynamics for a RigidDevice. More...
 
virtual ~RecursiveNewtonEuler ()
 Destructor.
 
rw::math::Vector3D getGravity () const
 Get the used gravity in base coordinates. More...
 
void setGravity (const rw::math::Vector3D<> &gravity)
 Set the gravity used. More...
 
rw::math::Vector3D getPayloadCOM () const
 Get the center of mass of the payload in the tool frame. More...
 
double getPayloadMass () const
 Get the mass of the payload. More...
 
rw::math::InertiaMatrix getPayloadInertia () const
 Get the inertia of the payload. More...
 
void setPayload (const rw::math::Vector3D<> &com, double payload, const rw::math::InertiaMatrix<> &inertia)
 Set the payload relative to the end frame of the device. More...
 
rw::math::Wrench6D getEnvironment () const
 Get the force and torque that the robot exerts on the environment at the TCP frame in base coordinates. More...
 
void setEnvironment (const rw::math::Wrench6D<> &wrench)
 Set the force and torque that the robot exerts on the environment at the TCP frame in base coordinates. More...
 
std::vector< MotiongetBodyMotion (const rw::kinematics::State &state, const rw::math::Q &dq, const rw::math::Q &ddq) const
 Get the Motion of each link and the payload for a device that have accelerating joints. More...
 
std::vector< rw::math::Wrench6D<> > getBodyNetForces (const std::vector< Motion > &motions, const rw::kinematics::State &state) const
 Determine the net force and torque acting on each link to achieve the given motion. More...
 
std::vector< rw::math::Wrench6D<> > getJointForces (const std::vector< rw::math::Wrench6D<>> &bodyNetForces, const rw::kinematics::State &state) const
 Determine the forces and torques acting in each joint to achieve the given net forces and torques on the links and payload. More...
 
std::vector< rw::math::Wrench6D<> > solve (const rw::kinematics::State &state, const rw::math::Q dq=rw::math::Q(), const rw::math::Q ddq=rw::math::Q()) const
 Do inverse dynamics for a robot in motion. More...
 
std::vector< double > solveMotorTorques (const rw::kinematics::State &state, const rw::math::Q &dq, const rw::math::Q &ddq) const
 Get the torque provided by each motor. More...
 
bool validate () const
 Check if solver will work for the given device - if not an exception will be thrown when trying to solve. More...
 

Detailed Description

The recursive Newton-Euler method is used for calculating inverse dynamics of a kinematic tree.

Constructor & Destructor Documentation

◆ RecursiveNewtonEuler()

Constructor for inverse dynamics for a RigidDevice.

Parameters
device[in] a rigid device

Member Function Documentation

◆ getBodyMotion()

std::vector<Motion> getBodyMotion ( const rw::kinematics::State state,
const rw::math::Q dq,
const rw::math::Q ddq 
) const

Get the Motion of each link and the payload for a device that have accelerating joints.

Parameters
state[in] the state of the device
dq[in] joint speeds
ddq[in] joint accelerations
Returns
vector of velocities and accelerations of the center of mass of each body in base coordinates

◆ getBodyNetForces()

std::vector<rw::math::Wrench6D<> > getBodyNetForces ( const std::vector< Motion > &  motions,
const rw::kinematics::State state 
) const

Determine the net force and torque acting on each link to achieve the given motion.

Parameters
motions[in] the motion of each link
state[in] state (position) of the robot
Returns
the net forces and torques acting on each link as a vector

◆ getEnvironment()

rw::math::Wrench6D getEnvironment ( ) const

Get the force and torque that the robot exerts on the environment at the TCP frame in base coordinates.

Returns
a 6D wrench

◆ getGravity()

rw::math::Vector3D getGravity ( ) const

Get the used gravity in base coordinates.

Returns
gravity vector

◆ getJointForces()

std::vector<rw::math::Wrench6D<> > getJointForces ( const std::vector< rw::math::Wrench6D<>> &  bodyNetForces,
const rw::kinematics::State state 
) const

Determine the forces and torques acting in each joint to achieve the given net forces and torques on the links and payload.

Parameters
bodyNetForces[in] the desired net forces and torques acting on each link in link local coordinate frames
state[in] state (position) of the robot
Returns
the net forces and torques acting on each joint in base coordinates.

◆ getPayloadCOM()

rw::math::Vector3D getPayloadCOM ( ) const

Get the center of mass of the payload in the tool frame.

Returns
center of mass of the payload

◆ getPayloadInertia()

rw::math::InertiaMatrix getPayloadInertia ( ) const

Get the inertia of the payload.

Returns
inertia of payload in end frame of device.

◆ getPayloadMass()

double getPayloadMass ( ) const

Get the mass of the payload.

Returns
mass of payload in end frame of device.

◆ setEnvironment()

void setEnvironment ( const rw::math::Wrench6D<> &  wrench)

Set the force and torque that the robot exerts on the environment at the TCP frame in base coordinates.

Parameters
wrench[in] the wrench the robot exerts on the environment

◆ setGravity()

void setGravity ( const rw::math::Vector3D<> &  gravity)

Set the gravity used.

Parameters
gravity[in] vector giving the gravity in base coordinates.

◆ setPayload()

void setPayload ( const rw::math::Vector3D<> &  com,
double  payload,
const rw::math::InertiaMatrix<> &  inertia 
)

Set the payload relative to the end frame of the device.

Parameters
com[in] the center of mass in the end frame.
payload[in] the mass of the payload
inertia[in] the inertia of the payload

◆ solve()

std::vector<rw::math::Wrench6D<> > solve ( const rw::kinematics::State state,
const rw::math::Q  dq = rw::math::Q(),
const rw::math::Q  ddq = rw::math::Q() 
) const

Do inverse dynamics for a robot in motion.

Parameters
state[in] state (position) of the robot
dq[in] the joint velocities
ddq[in] the joint accelerations
Returns
the wrenches working in each joint in base coordinates

◆ solveMotorTorques()

std::vector<double> solveMotorTorques ( const rw::kinematics::State state,
const rw::math::Q dq,
const rw::math::Q ddq 
) const

Get the torque provided by each motor.

Parameters
state[in] state (position) of the robot
dq[in] the joint velocities
ddq[in] the joint accelerations
Returns
the torques provided by each motor

◆ validate()

bool validate ( ) const

Check if solver will work for the given device - if not an exception will be thrown when trying to solve.

Returns
true if solver works for the given device, false otherwise.

The documentation for this class was generated from the following file: