53 : joint_trajectory_action_(joint_trajectory_action), controller_state_topic_(controller_state_topic)
77 std::copy(point.positions.begin(), point.positions.end(), std::ostream_iterator<double>(std::cout,
" "));
78 std::cout << std::endl;
87 std::ifstream input_file;
94 control_msgs::FollowJointTrajectoryGoal pre_goal;
95 control_msgs::FollowJointTrajectoryGoal goal;
98 goal.trajectory.joint_names.push_back(
"joint_a1");
99 goal.trajectory.joint_names.push_back(
"joint_a2");
100 goal.trajectory.joint_names.push_back(
"joint_a3");
101 goal.trajectory.joint_names.push_back(
"joint_a4");
102 goal.trajectory.joint_names.push_back(
"joint_a5");
103 goal.trajectory.joint_names.push_back(
"joint_a6");
104 goal.trajectory.joint_names.push_back(
"joint_a7");
105 pre_goal.trajectory.joint_names = goal.trajectory.joint_names;
106 double num_joints = goal.trajectory.joint_names.size();
109 std::getline(input_file, line);
112 while (std::getline(input_file, line))
114 std::stringstream lineStream(line);
116 trajectory_msgs::JointTrajectoryPoint point;
119 if (!std::getline(lineStream, cell,
','))
125 for (std::size_t i = 0; i < num_joints; ++i)
128 if (!std::getline(lineStream, cell,
','))
133 if (!std::getline(lineStream, cell,
','))
138 if (!std::getline(lineStream, cell,
','))
140 point.positions.push_back(atof(cell.c_str()));
143 if (!std::getline(lineStream, cell,
','))
145 point.velocities.push_back(atof(cell.c_str()));
148 if (!std::getline(lineStream, cell,
','))
153 goal.trajectory.points.push_back(point);
163 trajectory_msgs::JointTrajectoryPoint last_point;
167 std::cout <<
"Current State:" << std::endl;
170 std::cout <<
"^^ Goal point " << std::endl;
171 pre_goal.trajectory.points.push_back(last_point);
175 double max_velocity = 0.1;
176 double frequency = 200;
177 double q_delta = max_velocity / frequency;
178 double t_delta = 1 / frequency;
183 trajectory_msgs::JointTrajectoryPoint new_point = last_point;
187 new_point.time_from_start = time_from_start;
190 for (std::size_t i = 0; i < num_joints; ++i)
193 if (new_point.positions[i] < goal.trajectory.points.front().positions[i])
196 new_point.positions[i] =
197 std::min(new_point.positions[i] + q_delta, goal.trajectory.points.front().positions[i]);
198 new_point.velocities[i] = max_velocity;
204 new_point.velocities[i] = 0;
207 pre_goal.trajectory.points.push_back(new_point);
208 last_point = new_point;
221 for (std::size_t i = 0; i < goal.trajectory.points.size(); ++i)
void stateCB(const control_msgs::JointTrajectoryControllerState::ConstPtr &state)
Callback from ROS message.
#define ROS_ERROR_STREAM_NAMED(name, args)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
#define ROS_INFO_STREAM_NAMED(name, args)
std::string controller_state_topic_
control_msgs::JointTrajectoryControllerState current_state_
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
CSVToController(const std::string &joint_trajectory_action, const std::string &controller_state_topic)
Constructor.
void printPoint(trajectory_msgs::JointTrajectoryPoint &point)
actionlib::SimpleActionClient< control_msgs::FollowJointTrajectoryAction > joint_trajectory_action_
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
ROSCPP_DECL void spinOnce()
ros::Subscriber state_sub_
void loadAndRunCSV(const std::string &file_name)