18 #ifndef COB_TWIST_CONTROLLER_UTILS_SIMPSON_INTEGRATOR_H
19 #define COB_TWIST_CONTROLLER_UTILS_SIMPSON_INTEGRATOR_H
24 #include <kdl/jntarray.hpp>
25 #include <std_msgs/Float64MultiArray.h>
37 for (uint8_t i = 0; i <
dof_; i++)
60 for (
unsigned int i = 0; i <
dof_; ++i)
68 const KDL::JntArray& current_q,
69 std::vector<double>& pos,
70 std::vector<double>& vel)
76 bool value_valid =
false;
88 KDL::JntArray q_dot_avg(
dof_);
91 for (
unsigned int i = 0; i <
dof_; ++i)
93 ma_vel_[i]->addElement(q_dot_ik(i));
95 if (
ma_vel_[i]->calcMovingAverage(avg_vel))
97 q_dot_avg(i) = avg_vel;
101 q_dot_avg(i) = q_dot_ik(i);
112 for (
unsigned int i = 0; i <
dof_; ++i)
118 ma_pos_[i]->addElement(integration_value);
119 double avg_pos = 0.0;
120 if (!
ma_pos_[i]->calcMovingAverage(avg_pos))
123 avg_pos = integration_value;
126 pos.push_back(avg_pos);
127 vel.push_back(q_dot_avg(i));
137 for (
unsigned int i=0; i <
vel_last_.size(); ++i)
143 for (
unsigned int i=0; i < q_dot_avg.rows(); ++i)
172 #endif // COB_TWIST_CONTROLLER_UTILS_SIMPSON_INTEGRATOR_H