#include <JointSplineTrajectoryGenerator.h>

Public Member Functions | |
| virtual bool | configureHook () |
| JointSplineTrajectoryGenerator (const std::string &name) | |
| virtual bool | startHook () |
| virtual void | updateHook () |
| virtual | ~JointSplineTrajectoryGenerator () |
Protected Attributes | |
| RTT::OutputPort< bool > | buffer_ready_port_ |
| RTT::InputPort< std::vector < double > > | cmd_jnt_pos_port_ |
| RTT::InputPort< double > | command_period_port_ |
| RTT::OutputPort< std::vector < double > > | jnt_pos_port_ |
| RTT::Property< int > | number_of_joints_prop_ |
| RTT::OutputPort< bool > | trajectory_compleat_port_ |
| RTT::InputPort < trajectory_msgs::JointTrajectoryPoint > | trajectory_point_port_ |
Private Attributes | |
| bool | buffer_ready_ |
| std::vector< double > | des_jnt_pos_ |
| double | dt_ |
| int64_t | end_time_ |
| unsigned int | number_of_joints_ |
| int64_t | time_ |
| trajectory_msgs::JointTrajectoryPoint | trajectory_new_ |
| trajectory_msgs::JointTrajectoryPoint | trajectory_old_ |
| bool | trajectory_ready_ |
| std::vector < KDL::VelocityProfile_Spline > | vel_profile_ |
Definition at line 52 of file JointSplineTrajectoryGenerator.h.
| JointSplineTrajectoryGenerator::JointSplineTrajectoryGenerator | ( | const std::string & | name | ) | [explicit] |
Definition at line 44 of file JointSplineTrajectoryGenerator.cpp.
Definition at line 58 of file JointSplineTrajectoryGenerator.cpp.
| bool JointSplineTrajectoryGenerator::configureHook | ( | ) | [virtual] |
Reimplemented from RTT::base::TaskCore.
Definition at line 63 of file JointSplineTrajectoryGenerator.cpp.
| bool JointSplineTrajectoryGenerator::startHook | ( | ) | [virtual] |
Reimplemented from RTT::base::TaskCore.
Definition at line 97 of file JointSplineTrajectoryGenerator.cpp.
| void JointSplineTrajectoryGenerator::updateHook | ( | ) | [virtual] |
Reimplemented from RTT::base::TaskCore.
Definition at line 112 of file JointSplineTrajectoryGenerator.cpp.
bool JointSplineTrajectoryGenerator::buffer_ready_ [private] |
Definition at line 84 of file JointSplineTrajectoryGenerator.h.
RTT::OutputPort<bool> JointSplineTrajectoryGenerator::buffer_ready_port_ [protected] |
Definition at line 63 of file JointSplineTrajectoryGenerator.h.
RTT::InputPort<std::vector<double> > JointSplineTrajectoryGenerator::cmd_jnt_pos_port_ [protected] |
Definition at line 66 of file JointSplineTrajectoryGenerator.h.
RTT::InputPort<double> JointSplineTrajectoryGenerator::command_period_port_ [protected] |
Definition at line 70 of file JointSplineTrajectoryGenerator.h.
std::vector<double> JointSplineTrajectoryGenerator::des_jnt_pos_ [private] |
Definition at line 80 of file JointSplineTrajectoryGenerator.h.
double JointSplineTrajectoryGenerator::dt_ [private] |
Definition at line 88 of file JointSplineTrajectoryGenerator.h.
Definition at line 87 of file JointSplineTrajectoryGenerator.h.
RTT::OutputPort<std::vector<double> > JointSplineTrajectoryGenerator::jnt_pos_port_ [protected] |
Definition at line 65 of file JointSplineTrajectoryGenerator.h.
unsigned int JointSplineTrajectoryGenerator::number_of_joints_ [private] |
Definition at line 82 of file JointSplineTrajectoryGenerator.h.
RTT::Property<int> JointSplineTrajectoryGenerator::number_of_joints_prop_ [protected] |
Definition at line 72 of file JointSplineTrajectoryGenerator.h.
int64_t JointSplineTrajectoryGenerator::time_ [private] |
Definition at line 86 of file JointSplineTrajectoryGenerator.h.
RTT::OutputPort<bool> JointSplineTrajectoryGenerator::trajectory_compleat_port_ [protected] |
Definition at line 68 of file JointSplineTrajectoryGenerator.h.
trajectory_msgs::JointTrajectoryPoint JointSplineTrajectoryGenerator::trajectory_new_ [private] |
Definition at line 78 of file JointSplineTrajectoryGenerator.h.
trajectory_msgs::JointTrajectoryPoint JointSplineTrajectoryGenerator::trajectory_old_ [private] |
Definition at line 77 of file JointSplineTrajectoryGenerator.h.
RTT::InputPort<trajectory_msgs::JointTrajectoryPoint> JointSplineTrajectoryGenerator::trajectory_point_port_ [protected] |
Definition at line 62 of file JointSplineTrajectoryGenerator.h.
bool JointSplineTrajectoryGenerator::trajectory_ready_ [private] |
Definition at line 83 of file JointSplineTrajectoryGenerator.h.
std::vector<KDL::VelocityProfile_Spline> JointSplineTrajectoryGenerator::vel_profile_ [private] |
Definition at line 75 of file JointSplineTrajectoryGenerator.h.