Public Member Functions | Private Member Functions | Private Attributes | List of all members
generic_control_toolbox::JointPositionIntegrator Class Reference

#include <joint_position_integrator.hpp>

Public Member Functions

 JointPositionIntegrator (ros::NodeHandle &nh)
 
void reset ()
 
KDL::JntArray update (const KDL::JntArray &q_dot, const KDL::JntArray &q, float dt)
 
Eigen::VectorXd update (const Eigen::VectorXd &q_dot, const Eigen::VectorXd &q, float dt)
 
 ~JointPositionIntegrator ()
 

Private Member Functions

bool init ()
 

Private Attributes

bool got_state_
 
float max_joint_error_
 
ros::NodeHandle nh_
 
KDL::JntArray virt_q_
 

Detailed Description

Implement a joint position integrator which produces joint position references given a joint velocity target.

Definition at line 13 of file joint_position_integrator.hpp.

Constructor & Destructor Documentation

◆ JointPositionIntegrator()

generic_control_toolbox::JointPositionIntegrator::JointPositionIntegrator ( ros::NodeHandle nh)

Definition at line 5 of file joint_position_integrator.cpp.

◆ ~JointPositionIntegrator()

generic_control_toolbox::JointPositionIntegrator::~JointPositionIntegrator ( )
inline

Definition at line 17 of file joint_position_integrator.hpp.

Member Function Documentation

◆ init()

bool generic_control_toolbox::JointPositionIntegrator::init ( )
private

Get the parameters for the integrator.

Definition at line 67 of file joint_position_integrator.cpp.

◆ reset()

void generic_control_toolbox::JointPositionIntegrator::reset ( )

Reset the integrator's state.

Definition at line 16 of file joint_position_integrator.cpp.

◆ update() [1/2]

KDL::JntArray generic_control_toolbox::JointPositionIntegrator::update ( const KDL::JntArray q_dot,
const KDL::JntArray q,
float  dt 
)

Produce an updated joint position vector for a given set of joint velocities.

The output is q = sat(q + q_dot * dt), where the function sat(.) saturates the output if any joint exceeds the configured max_joint_error.

Parameters
q_dotThe array of joint velocities to be integrated.
qThe current joint state.
dtThe integration delta.
Returns
An updated set of joint positions.

Definition at line 18 of file joint_position_integrator.cpp.

◆ update() [2/2]

Eigen::VectorXd generic_control_toolbox::JointPositionIntegrator::update ( const Eigen::VectorXd &  q_dot,
const Eigen::VectorXd &  q,
float  dt 
)

Definition at line 43 of file joint_position_integrator.cpp.

Member Data Documentation

◆ got_state_

bool generic_control_toolbox::JointPositionIntegrator::got_state_
private

Definition at line 45 of file joint_position_integrator.hpp.

◆ max_joint_error_

float generic_control_toolbox::JointPositionIntegrator::max_joint_error_
private

Definition at line 44 of file joint_position_integrator.hpp.

◆ nh_

ros::NodeHandle generic_control_toolbox::JointPositionIntegrator::nh_
private

Definition at line 42 of file joint_position_integrator.hpp.

◆ virt_q_

KDL::JntArray generic_control_toolbox::JointPositionIntegrator::virt_q_
private

Definition at line 43 of file joint_position_integrator.hpp.


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


generic_control_toolbox
Author(s): diogo
autogenerated on Mon Feb 28 2022 22:24:38