22 #include <std_msgs/Float64.h>
23 #include <trajectory_msgs/JointTrajectory.h>
24 #include <kdl/jntarray.hpp>
74 double a = 0.6, b = 0.4, c = 0,
d = 0;
77 trajectory_msgs::JointTrajectoryPoint traj_point;
78 traj_point.positions.assign(
dof_, 0.0);
81 std::vector<std::string> joint_names;
89 joint_names.push_back(
"torso_2_joint");
90 joint_names.push_back(
"torso_3_joint");
95 period = time - last_update_time;
96 last_update_time = time;
99 std::vector<double> next_q;
100 std::vector<double> next_q_dot;
120 trajectory_msgs::JointTrajectory traj_msg;
121 traj_msg.points.push_back(traj_point);
122 traj_msg.joint_names = joint_names;
126 std_msgs::Float64 q_msg;
128 std_msgs::Float64 q_dot_msg;
130 std_msgs::Float64 simpson_q_msg;
132 std_msgs::Float64 euler_q_msg;
134 std_msgs::Float64 derived_simpson_q_dot_msg;
174 int main(
int argc,
char **argv)
176 ros::init(argc, argv,
"test_trajectory_command_execution_node");