60 state_sub_ = nh_.subscribe<control_msgs::JointTrajectoryControllerState>(topic, 1, &ControllerToCSV::stateCB,
this);
63 waitForSubscriber(state_sub_);
78 ControllerToCSV::~ControllerToCSV()
83 bool ControllerToCSV::recordAll()
85 return record_hz_ == 0;
88 void ControllerToCSV::stateCB(
const control_msgs::JointTrajectoryControllerState::ConstPtr& state)
94 states_.push_back(current_state_);
101 current_state_ = *state;
106 void ControllerToCSV::startRecording(
const std::string& file_name)
109 file_name_ = file_name;
115 recording_started_ =
true;
121 non_realtime_loop_ = nh_.createTimer(update_freq, &ControllerToCSV::update,
this);
130 if (current_state_.joint_names.empty())
135 first_update_ =
false;
139 const double freq = 1.0 / (
event.current_real -
event.last_real).toSec();
141 "Updating at " << freq <<
" hz, total: "
142 << (
ros::Time::now() - timestamps_.front()).toSec() <<
" seconds");
145 states_.push_back(current_state_);
151 void ControllerToCSV::stopRecording()
153 non_realtime_loop_.stop();
157 bool ControllerToCSV::writeToFile()
159 std::cout <<
"Writing data to file " << std::endl;
163 std::cout <<
"No controller states populated" << std::endl;
167 std::ofstream output_file;
168 output_file.open(file_name_.c_str());
171 output_file <<
"timestamp,";
172 for (std::size_t j = 0; j < states_[0].joint_names.size(); ++j)
174 output_file << states_[0].joint_names[j] <<
"_desired_pos," << states_[0].joint_names[j] <<
"_desired_vel,"
175 << states_[0].joint_names[j] <<
"_actual_pos," << states_[0].joint_names[j] <<
"_actual_vel,"
176 << states_[0].joint_names[j] <<
"_error_pos," << states_[0].joint_names[j] <<
"_error_vel,";
178 output_file << std::endl;
184 double start_time = timestamps_[0].toSec();
186 for (std::size_t i = 0; i < states_.size(); ++i)
189 output_file << timestamps_[i].toSec() - start_time <<
",";
192 for (std::size_t j = 0; j < states_[i].joint_names.size(); ++j)
195 output_file << states_[i].desired.positions[j] <<
"," << states_[i].desired.velocities[j] <<
","
196 << states_[i].actual.positions[j] <<
"," << states_[i].actual.velocities[j] <<
","
197 << states_[i].error.positions[j] <<
"," << states_[i].error.velocities[j] <<
",";
200 output_file << std::endl;
203 std::cout <<
"Wrote to file: " << file_name_ << std::endl;
207 bool ControllerToCSV::waitForSubscriber(
const ros::Subscriber& sub,
const double& wait_time)
224 while (num_existing_subscribers == 0)
230 << wait_time <<
" seconds.");
247 <<
" seconds to connect to a subscriber. "
249 << num_existing_subscribers <<
" total subsribers");