csv_to_controller.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2015, University of Colorado, Boulder
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Univ of CO, Boulder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Dave Coleman
36  Desc: Records a ros_control ControllerState data to CSV for Matlab/etc analysis
37 */
38 
40 
41 // Basic file operations
42 #include <iostream>
43 #include <fstream>
44 #include <sstream>
45 #include <stdlib.h>
46 #include <iterator>
47 #include <vector>
48 #include <string>
49 
51 {
52 CSVToController::CSVToController(const std::string& joint_trajectory_action, const std::string& controller_state_topic)
53  : joint_trajectory_action_(joint_trajectory_action), controller_state_topic_(controller_state_topic)
54 {
55  ROS_INFO_STREAM_NAMED("csv_to_controller", "Waiting for action server");
57 
58  // State subscriber
59  state_sub_ = nh_.subscribe<control_msgs::JointTrajectoryControllerState>(controller_state_topic_, 1,
61 
62  // Wait for states to populate
63  ros::spinOnce();
64  ros::Duration(0.5).sleep();
65 
66  ROS_INFO_STREAM_NAMED("csv_to_controller", "CSVToController Ready.");
67 }
68 
69 void CSVToController::stateCB(const control_msgs::JointTrajectoryControllerState::ConstPtr& state)
70 {
71  current_state_ = *state;
72 }
73 
74 void CSVToController::printPoint(trajectory_msgs::JointTrajectoryPoint& point)
75 {
76  // Show new line
77  std::copy(point.positions.begin(), point.positions.end(), std::ostream_iterator<double>(std::cout, " "));
78  std::cout << std::endl;
79 }
80 
81 // Start the data collection
82 void CSVToController::loadAndRunCSV(const std::string& file_name)
83 {
84  file_name_ = file_name;
85 
86  // Open file
87  std::ifstream input_file;
88  input_file.open(file_name_.c_str());
89 
90  // Settings
91  std::string line;
92  std::string cell;
93 
94  control_msgs::FollowJointTrajectoryGoal pre_goal; // moving to start state
95  control_msgs::FollowJointTrajectoryGoal goal; // csv file
96 
97  // Populate joint names
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();
107 
108  // Skip header
109  std::getline(input_file, line);
110 
111  // For each line/row
112  while (std::getline(input_file, line))
113  {
114  std::stringstream lineStream(line);
115 
116  trajectory_msgs::JointTrajectoryPoint point;
117 
118  // TIME FROM START
119  if (!std::getline(lineStream, cell, ','))
120  ROS_ERROR_STREAM_NAMED("csv_to_controller", "no joint value");
121 
122  point.time_from_start = ros::Duration(atof(cell.c_str()));
123 
124  // For each item/column
125  for (std::size_t i = 0; i < num_joints; ++i)
126  {
127  // DESIRED POSITION
128  if (!std::getline(lineStream, cell, ','))
129  ROS_ERROR_STREAM_NAMED("csv_to_controller", "no joint value");
130  // UNUSED
131 
132  // DESIRED VELOCITY
133  if (!std::getline(lineStream, cell, ','))
134  ROS_ERROR_STREAM_NAMED("csv_to_controller", "no joint value");
135  // UNUSED
136 
137  // ACTUAL POSITION
138  if (!std::getline(lineStream, cell, ','))
139  ROS_ERROR_STREAM_NAMED("csv_to_controller", "no joint value");
140  point.positions.push_back(atof(cell.c_str()));
141 
142  // ACTUAL VELOCITY
143  if (!std::getline(lineStream, cell, ','))
144  ROS_ERROR_STREAM_NAMED("csv_to_controller", "no joint value");
145  point.velocities.push_back(atof(cell.c_str()));
146 
147  // COMMANDED VEL
148  if (!std::getline(lineStream, cell, ','))
149  ROS_ERROR_STREAM_NAMED("csv_to_controller", "no joint value");
150  // UNUSED
151  }
152 
153  goal.trajectory.points.push_back(point);
154  } // while
155 
156  // Check that we have a current state
157  if (current_state_.actual.positions.empty())
158  {
159  ROS_ERROR_STREAM_NAMED("csv_to_controller", "Unable to find current state msg");
160  return;
161  }
162  // Add current state to start of trajectory
163  trajectory_msgs::JointTrajectoryPoint last_point;
164  last_point.positions = current_state_.actual.positions;
165  last_point.velocities = current_state_.actual.velocities;
166 
167  std::cout << "Current State:" << std::endl;
168  printPoint(last_point);
169  printPoint(goal.trajectory.points.front());
170  std::cout << "^^ Goal point " << std::endl;
171  pre_goal.trajectory.points.push_back(last_point);
172 
173  // Interpolate from first point
174  bool done = false;
175  double max_velocity = 0.1; // m/s or radians/s
176  double frequency = 200; // hz
177  double q_delta = max_velocity / frequency; // m
178  double t_delta = 1 / frequency;
179  ros::Duration time_from_start(1);
180  while (!done)
181  {
182  done = true;
183  trajectory_msgs::JointTrajectoryPoint new_point = last_point;
184 
185  // Time change
186  time_from_start += ros::Duration(t_delta);
187  new_point.time_from_start = time_from_start;
188 
189  // Position change
190  for (std::size_t i = 0; i < num_joints; ++i) // each joint
191  {
192  // Do we need to move this joint foward?
193  if (new_point.positions[i] < goal.trajectory.points.front().positions[i])
194  {
195  // Do not allow to go past goal point
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;
199  done = false;
200  }
201  else
202  {
203  // Maintain velocity
204  new_point.velocities[i] = 0;
205  }
206  }
207  pre_goal.trajectory.points.push_back(new_point);
208  last_point = new_point;
209 
210  printPoint(new_point);
211  }
212 
213  // std::cout << "TRAJECTORY: " << trajectory << std::endl;
214  // std::cout << "TRAJECTORY: " << goal.trajectory << std::endl;
215 
216  ROS_INFO_STREAM_NAMED("temp", "Sleeping for " << time_from_start.toSec());
217  pre_goal.trajectory.header.stamp = ros::Time::now() + ros::Duration(0.5);
219  ros::Duration(time_from_start).sleep();
220 
221  for (std::size_t i = 0; i < goal.trajectory.points.size(); ++i)
222  {
223  printPoint(goal.trajectory.points[i]);
224  }
225 
226  ROS_INFO_STREAM_NAMED("csv_to_controller", "Preparing to follow CSV path");
227  ros::Duration(0.5).sleep();
228  goal.trajectory.header.stamp = ros::Time::now() + ros::Duration(0.5);
230 }
231 
232 } // namespace ros_control_boilerplate
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)
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())
static Time now()
bool sleep() const
ROSCPP_DECL void spinOnce()
void loadAndRunCSV(const std::string &file_name)


ros_control_boilerplate
Author(s): Dave Coleman
autogenerated on Mon Feb 28 2022 23:27:26