Public Member Functions | Private Attributes
SimpsonIntegrator Class Reference

#include <simpson_integrator.h>

List of all members.

Public Member Functions

void resetIntegration ()
 SimpsonIntegrator (const uint8_t dof, const double integrator_smoothing=0.2)
bool updateIntegration (const KDL::JntArray &q_dot_ik, const KDL::JntArray &current_q, std::vector< double > &pos, std::vector< double > &vel)
 ~SimpsonIntegrator ()

Private Attributes

uint8_t dof_
double integrator_smoothing_
ros::Time last_update_time_
std::vector
< MovingAvgBase_double_t * > 
ma_pos_
std::vector
< MovingAvgBase_double_t * > 
ma_vel_
std::vector< double > vel_before_last_
std::vector< double > vel_last_

Detailed Description

Definition at line 29 of file simpson_integrator.h.


Constructor & Destructor Documentation

SimpsonIntegrator::SimpsonIntegrator ( const uint8_t  dof,
const double  integrator_smoothing = 0.2 
) [inline, explicit]

nh_ = ros::NodeHandle("simpson_debug"); q_dot_ik_pub_ = nh_.advertise<std_msgs::Float64MultiArray>("q_dot_ik", 1); q_dot_avg_pub_ = nh_.advertise<std_msgs::Float64MultiArray>("q_dot_avg", 1); q_simpson_pub_ = nh_.advertise<std_msgs::Float64MultiArray>("q_simpson", 1); q_simpson_avg_pub_ = nh_.advertise<std_msgs::Float64MultiArray>("q_simpson_avg", 1);

Definition at line 32 of file simpson_integrator.h.

Definition at line 50 of file simpson_integrator.h.


Member Function Documentation

Definition at line 53 of file simpson_integrator.h.

bool SimpsonIntegrator::updateIntegration ( const KDL::JntArray q_dot_ik,
const KDL::JntArray current_q,
std::vector< double > &  pos,
std::vector< double > &  vel 
) [inline]

std_msgs::Float64MultiArray q_dot_ik_msg; std_msgs::Float64MultiArray q_dot_avg_msg;

q_dot_ik_msg.data.push_back(q_dot_ik(i)); q_dot_avg_msg.data.push_back(q_dot_avg(i));

std_msgs::Float64MultiArray q_simpson_msg; std_msgs::Float64MultiArray q_simpson_avg_msg;

q_simpson_msg.data.push_back(integration_value); q_simpson_avg_msg.data.push_back(avg_pos);

q_dot_ik_pub_.publish(q_dot_ik_msg); q_dot_avg_pub_.publish(q_dot_avg_msg); q_simpson_pub_.publish(q_simpson_msg); q_simpson_avg_pub_.publish(q_simpson_avg_msg);

Definition at line 67 of file simpson_integrator.h.


Member Data Documentation

uint8_t SimpsonIntegrator::dof_ [private]

Definition at line 159 of file simpson_integrator.h.

Definition at line 160 of file simpson_integrator.h.

Definition at line 162 of file simpson_integrator.h.

Definition at line 158 of file simpson_integrator.h.

Definition at line 157 of file simpson_integrator.h.

std::vector<double> SimpsonIntegrator::vel_before_last_ [private]

Definition at line 161 of file simpson_integrator.h.

std::vector<double> SimpsonIntegrator::vel_last_ [private]

Definition at line 161 of file simpson_integrator.h.


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


cob_twist_controller
Author(s): Felix Messmer , Marco Bezzon , Christoph Mark , Francisco Moreno
autogenerated on Thu Jun 6 2019 21:19:26