Class InverseDynamicsSolver

Class Documentation

class InverseDynamicsSolver

Public Functions

inline virtual ~InverseDynamicsSolver()

Virtual destructor.

virtual void initialize(rclcpp::node_interfaces::NodeParametersInterface::ConstSharedPtr parameters_interface = nullptr, const std::string &param_namespace = "", const std::string &robot_description = "") = 0

Initialize the plugin object.

Since pluginlib requires the implementation to have a parameterless constructor, the objects are initialized through this method

Parameters:
  • parameters_interface[in] the node parameters interface through which the parameters are passed

  • param_namespace[in] namespace for the node parameters

  • robot_description[in] robot URDF in string format

inline virtual std::tuple<Eigen::MatrixXd, Eigen::VectorXd, Eigen::VectorXd> getDynamicParameters(const Eigen::VectorXd &joint_positions, const Eigen::VectorXd &joint_velocities) const

Get all the dynamic parameters at once.

Parameters:
  • joint_positions[in] joint positions

  • joint_velocities[in] joint velocities

Returns:

inertia matrix, Coriolis vector, corresponding to C(q,qd)*qd, and gravity vector

virtual Eigen::MatrixXd getInertiaMatrix(const Eigen::VectorXd &joint_positions) const = 0

Get the inertia matrix.

Parameters:

joint_positions[in] joint positions

Returns:

inertia matrix

virtual Eigen::VectorXd getCoriolisVector(const Eigen::VectorXd &joint_positions, const Eigen::VectorXd &joint_velocities) const = 0

Get the Coriolis vector.

Parameters:
  • joint_positions[in] joint positions

  • joint_velocities[in] joint velocities

Returns:

coriolis vector, corresponding to C(q,qd)*qd

virtual Eigen::VectorXd getGravityVector(const Eigen::VectorXd &joint_positions) const = 0

Get the gravity vector.

Parameters:

joint_positions[in] joint positions

Returns:

gravity vector

virtual Eigen::VectorXd getFrictionVector(const Eigen::VectorXd &joint_velocities) const = 0

Get the vector of friction torques.

Parameters:

joint_velocities[in] joint velocities

Returns:

friction vector

inline virtual Eigen::VectorXd getTorques(const Eigen::VectorXd &joint_positions, const Eigen::VectorXd &joint_velocities, const Eigen::VectorXd &joint_accelerations) const

Get the vector of torques due to Coriolis effects, inertia and gravity.

Parameters:
  • joint_positions[in] joint positions

  • joint_velocities[in] joint velocities

  • joint_accelerations[in] joint accelerations

Returns:

torques vector

Protected Functions

inline InverseDynamicsSolver()