19 #include <std_msgs/String.h>
20 #include <std_msgs/Float64MultiArray.h>
21 #include <sensor_msgs/JointState.h>
22 #include <control_msgs/JointTrajectoryControllerState.h>
24 #include <control_msgs/FollowJointTrajectoryAction.h>
28 #include <std_srvs/Trigger.h>
29 #include <cob_srvs/SetString.h>
30 #include <cob_srvs/SetFloat.h>
63 trajectory_msgs::JointTrajectory
traj_;
82 ROS_INFO(
"Waiting for operationmode service to become available");
93 double maxError = 0.7;
94 double overlap_time = 0.4;
105 ROS_ERROR(
"Parameter 'joint_names' not set");
130 ROS_INFO(
"starting controller with DOF: %d PTPvel: %f PTPAcc: %f maxError %f",
DOF, PTPvel, PTPacc, maxError);
143 ROS_INFO(
"Setting controller frequency to %f HZ", frequency);
148 ROS_WARN(
"Parameter 'frequency' not available, setting to default value: %f Hz", frequency);
155 ROS_INFO(
"Stopping trajectory controller.");
167 ROS_INFO(
"Setting velocity to %f", req.data);
175 ROS_INFO(
"Setting acceleration to %f", req.data);
186 void state_callback(
const control_msgs::JointTrajectoryControllerStatePtr& message)
188 std::vector<double> positions = message->actual.positions;
189 for(
unsigned int i = 0; i < positions.size(); i++)
200 cob_srvs::SetString opmode;
201 opmode.request.data =
"velocity";
206 ROS_INFO(
"waiting for component to go to velocity mode");
216 std::vector<double> traj_start;
219 ROS_INFO(
"There is a old trajectory currently running");
221 trajectory_msgs::JointTrajectory temp_traj;
222 temp_traj = trajectory;
224 trajectory_msgs::JointTrajectoryPoint p;
225 p.positions.resize(
DOF);
226 p.velocities.resize(
DOF);
227 p.accelerations.resize(
DOF);
228 for(
int i = 0; i<
DOF; i++)
230 p.positions.at(i) = traj_start.at(i);
231 p.velocities.at(i) = 0.0;
232 p.accelerations.at(i) = 0.0;
234 std::vector<trajectory_msgs::JointTrajectoryPoint>::iterator it;
235 it = temp_traj.points.begin();
236 temp_traj.points.insert(it,p);
238 for(
int i = 0; i<
DOF; i++)
241 p.velocities.at(i) = 0.0;
242 p.accelerations.at(i) = 0.0;
244 it = temp_traj.points.begin();
245 temp_traj.points.insert(it,p);
246 for(
int i = 0; i<
DOF; i++)
249 p.velocities.at(i) = 0.0;
250 p.accelerations.at(i) = 0.0;
252 it = temp_traj.points.begin();
253 temp_traj.points.insert(it,p);
254 for(
int i = 0; i<
DOF; i++)
257 p.velocities.at(i) = 0.0;
258 p.accelerations.at(i) = 0.0;
260 it = temp_traj.points.begin();
261 temp_traj.points.insert(it,p);
262 for(
int i = 0; i<
DOF; i++)
265 p.velocities.at(i) = 0.0;
266 p.accelerations.at(i) = 0.0;
268 it = temp_traj.points.begin();
269 temp_traj.points.insert(it,p);
276 trajectory_msgs::JointTrajectory temp_traj;
277 temp_traj = trajectory;
278 if(temp_traj.points.size() == 1)
286 trajectory_msgs::JointTrajectoryPoint p;
287 p.positions.resize(
DOF);
288 p.velocities.resize(
DOF);
289 p.accelerations.resize(
DOF);
290 for(
int i = 0; i<
DOF; i++)
292 p.positions.at(i) = traj_start.at(i);
293 p.velocities.at(i) = 0.0;
294 p.accelerations.at(i) = 0.0;
296 std::vector<trajectory_msgs::JointTrajectoryPoint>::iterator it;
297 it = temp_traj.points.begin();
298 temp_traj.points.insert(it,p);
328 ROS_INFO(
"Received new goal trajectory with %lu points",goal->trajectory.points.size());
364 ROS_INFO(
"Preempted trajectory action");
367 std::vector<double> des_vel;
375 std_msgs::Float64MultiArray target_joint_vel;
376 for(
int i=0; i<
DOF; i++)
378 target_joint_vel.data.push_back(des_vel.at(i));
386 ROS_INFO(
"An controller error occured!");
395 std_msgs::Float64MultiArray target_joint_vel;
396 for(
int i=0; i<
DOF; i++)
398 target_joint_vel.data.push_back(0.0);
410 int main(
int argc,
char ** argv)
412 ros::init(argc, argv,
"cob_trajectory_controller");