#include <simpson_integrator.h>
Definition at line 29 of file simpson_integrator.h.
SimpsonIntegrator::SimpsonIntegrator |
( |
const uint8_t |
dof, |
|
|
const double |
integrator_smoothing = 0.2 |
|
) |
| |
|
inlineexplicit |
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.
SimpsonIntegrator::~SimpsonIntegrator |
( |
| ) |
|
|
inline |
void SimpsonIntegrator::resetIntegration |
( |
| ) |
|
|
inline |
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.
uint8_t SimpsonIntegrator::dof_ |
|
private |
double SimpsonIntegrator::integrator_smoothing_ |
|
private |
ros::Time SimpsonIntegrator::last_update_time_ |
|
private |
std::vector<double> SimpsonIntegrator::vel_before_last_ |
|
private |
std::vector<double> SimpsonIntegrator::vel_last_ |
|
private |
The documentation for this class was generated from the following file: