5 #include <ram_msgs/AdditiveManufacturingTrajectory.h> 6 #include <ram_utils/BufferParams.h> 7 #include <ram_utils/ExportTrajectory.h> 8 #include <ram_utils/ImportTrajectory.h> 9 #include <ram_utils/UnmodifiedTrajectory.h> 25 std::vector<ram_msgs::AdditiveManufacturingTrajectory>
traj_msgs;
89 ram_utils::BufferParams::Response &res)
93 ram_msgs::AdditiveManufacturingTrajectory
trajectory;
94 switch (req.button_id)
102 res.error =
"Start of the buffer";
112 res.error =
"End of the buffer";
130 ram_utils::UnmodifiedTrajectory::Response &res)
135 if (msg.generated == req.generated)
137 res.trajectory = msg;
147 size_t last_index = full_path.find_last_of(
"/");
148 std::string file_name = full_path.substr(last_index + 1, full_path.size());
150 last_index = file_name.find_last_of(
"\\");
151 file_name = file_name.substr(last_index + 1, file_name.size());
153 last_index = file_name.find_last_of(
".");
154 if (last_index == std::string::npos)
157 return file_name.substr(last_index + 1, file_name.size());
161 ram_utils::ExportTrajectory::Response &res)
166 if (req.file_name.find(
"smb-share:") != std::string::npos)
168 res.error =
"Cannot export file to network!\n" + req.file_name;
173 if (file_extension.compare(
"bag") != 0)
175 res.error = req.file_name +
" is not a bag file";
182 res.error =
"Current trajectory is empty";
187 ram_msgs::AdditiveManufacturingTrajectory unmodified_current_traj = current_traj;
189 if (current_traj.poses.size() == 0)
191 res.error =
"Current trajectory is empty";
196 bool trajectory_in_buffer =
false;
199 if (current_traj.generated != msg.generated)
202 trajectory_in_buffer =
true;
203 if (current_traj.modified != msg.modified)
205 unmodified_current_traj = msg;
210 if (!trajectory_in_buffer)
212 res.error =
"Corresponding unmodified trajectory does not exist in the buffer";
223 export_trajectoy_bag.
close();
227 export_trajectoy_bag.
close();
229 res.error = e.what();
237 ram_utils::ImportTrajectory::Response &res)
243 if (file_extension.compare(
"bag") != 0)
245 res.error = req.file_name +
" is not a bag file";
251 std::vector<ram_msgs::AdditiveManufacturingTrajectory> msgs_from_file;
255 std::vector<std::string> topics;
256 topics.push_back(std::string(
"ram/trajectory"));
261 ram_msgs::AdditiveManufacturingTrajectory::ConstPtr
s =
262 m.instantiate<ram_msgs::AdditiveManufacturingTrajectory>();
264 msgs_from_file.push_back(*s);
267 import_trajectoy_bag.
close();
271 import_trajectoy_bag.
close();
273 res.error = e.what();
277 if (msgs_from_file.size() != 2)
279 res.error =
"Unable to import trajectory";
284 ram_msgs::AdditiveManufacturingTrajectory
trajectory = msgs_from_file[0];
285 ram_msgs::AdditiveManufacturingTrajectory unmodified_trajectory = msgs_from_file[1];
287 if (trajectory.poses.size() == 0)
289 res.error =
"Trajectory is empty";
319 bool error_in_first_bag =
false;
320 bool error_in_second_bag =
false;
326 std::vector<std::string> topics;
327 topics.push_back(std::string(
"ram/trajectory"));
333 ram_msgs::AdditiveManufacturingTrajectory::ConstPtr
s =
334 m.instantiate<ram_msgs::AdditiveManufacturingTrajectory>();
347 std::string file(getenv(
"HOME"));
348 file +=
"/.ros/ram_buffer_trajectory.bag";
350 if (std::remove(file.c_str()) == 0)
353 error_in_first_bag =
true;
360 std::vector<std::string> topics;
361 topics.push_back(std::string(
"ram/trajectory"));
367 ram_msgs::AdditiveManufacturingTrajectory::ConstPtr
s =
368 m.instantiate<ram_msgs::AdditiveManufacturingTrajectory>();
379 std::string file(getenv(
"HOME"));
380 file +=
"/.ros/ram_buffer_unmodified_trajectory.bag";
382 if (std::remove(file.c_str()) == 0)
385 error_in_second_bag =
true;
388 if (error_in_first_bag || error_in_second_bag)
395 pub = nh.
advertise<ram_msgs::AdditiveManufacturingTrajectory>(
"ram/trajectory",
msg_to_keep,
true);
const unsigned msg_to_keep(10)
void publish(const boost::shared_ptr< M > &message) const
void open(std::string const &filename, uint32_t mode=bagmode::Read)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool exportTrajectoryCallback(ram_utils::ExportTrajectory::Request &req, ram_utils::ExportTrajectory::Response &res)
unsigned last_msg_published
std::mutex unmodified_msgs_mutex
std::unique_ptr< ros::NodeHandle > nh
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL const std::string & getName()
ram_msgs::AdditiveManufacturingTrajectory trajectory
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
std::vector< ram_msgs::AdditiveManufacturingTrajectory > traj_msgs
const std::string & getPublisherName() const
bool trajectoryBufferCallback(ram_utils::BufferParams::Request &req, ram_utils::BufferParams::Response &res)
std::vector< ram_msgs::AdditiveManufacturingTrajectory > unmodified_traj_msgs
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_WARN_STREAM(args)
int main(int argc, char **argv)
bool getUnmodifiedTrajectoryCallback(ram_utils::UnmodifiedTrajectory::Request &req, ram_utils::UnmodifiedTrajectory::Response &res)
bool importTrajectoryCallback(ram_utils::ImportTrajectory::Request &req, ram_utils::ImportTrajectory::Response &res)
void saveTrajectoryCallback(const ros::MessageEvent< ram_msgs::AdditiveManufacturingTrajectory > &msg_event)
ROSCPP_DECL void shutdown()
#define ROS_ERROR_STREAM(args)
void mySigintHandler(int)
std::string fileExtension(const std::string full_path)
void write(std::string const &topic, ros::MessageEvent< T > const &event)
boost::shared_ptr< M > getMessage() const
ROSCPP_DECL void waitForShutdown()