update_logger.cpp
Go to the documentation of this file.
1 
28 #include <boost/filesystem.hpp>
29 #include <ros/console.h>
31 #include <ros/package.h>
32 #include <Eigen/Core>
33 
35 
36 namespace stomp_moveit
37 {
38 namespace update_filters
39 {
40 
41 UpdateLogger::UpdateLogger():
42  name_("UpdateLogger")
43 {
44 
45 }
46 
47 UpdateLogger::~UpdateLogger()
48 {
49  // TODO Auto-generated destructor stub
50 }
51 
52 bool UpdateLogger::initialize(moveit::core::RobotModelConstPtr robot_model_ptr,
53  const std::string& group_name,const XmlRpc::XmlRpcValue& config)
54 {
55  format_ = Eigen::IOFormat(Eigen::StreamPrecision,0," ","\n");
56  group_name_ = group_name;
57  return configure(config);
58 }
59 
61 {
62  // check parameter presence
63  auto members = {"filename","directory","package"};
64  for(auto& m : members)
65  {
66  if(!config.hasMember(m))
67  {
68  ROS_ERROR("%s failed to find one or more required parameters",getName().c_str());
69  return false;
70  }
71  }
72 
73  XmlRpc::XmlRpcValue c = config;
74  try
75  {
76  filename_ = static_cast<std::string>(c["filename"]);
77  directory_ = static_cast<std::string>(c["directory"]);
78  package_ = static_cast<std::string>(c["package"]);
79  }
80  catch(XmlRpc::XmlRpcException& e)
81  {
82  ROS_ERROR("%s failed to find the required parameters",getName().c_str());
83  return false;
84  }
85 
86  return true;
87 }
88 
89 bool UpdateLogger::setMotionPlanRequest(const planning_scene::PlanningSceneConstPtr& planning_scene,
90  const moveit_msgs::MotionPlanRequest &req,
91  const stomp_core::StompConfiguration &config,
92  moveit_msgs::MoveItErrorCodes& error_code)
93 {
94  using namespace boost::filesystem;
95 
96  stomp_config_ = config;
97 
98  std::string full_dir_name = ros::package::getPath(package_) + "/" + directory_;
99  full_file_name_ = full_dir_name + "/" + filename_;
100  path dir_path(full_dir_name);
101 
102  if(!boost::filesystem::is_directory(dir_path))
103  {
104  // create directory
105  if(!boost::filesystem::create_directory(dir_path))
106  {
107  ROS_ERROR("Unable to create the update logging directory in the path %s",full_dir_name.c_str());
108  return false;
109  }
110  }
111 
112  // open file
113  file_stream_.open(full_file_name_);
114  if(!file_stream_.is_open())
115  {
116  ROS_ERROR("Unable to create/open update log file %s",full_file_name_.c_str());
117  return false;
118  }
119 
120  // clear stream
121  stream_.str("");
122 
123  return true;
124 }
125 
126 bool UpdateLogger::filter(std::size_t start_timestep,std::size_t num_timesteps,int iteration_number,
127  const Eigen::MatrixXd& parameters,
128  Eigen::MatrixXd& updates,
129  bool& filtered)
130 {
131 
132  stream_<<updates.format(format_)<<std::endl;
133  filtered = false;
134  return true;
135 }
136 
137 void UpdateLogger::done(bool success, int total_iterations,double final_cost,const Eigen::MatrixXd& parameters)
138 {
139  // creating header
140  std::string header = R"(# num_iterations: @iterations
141 # num_timesteps: @timesteps
142 # num_dimensions: @dimensions
143 # matrix_rows: @rows
144 # matrix_cols: @cols)";
145 
146  // replacing values into header
147  int rows = stomp_config_.num_dimensions * total_iterations;
148  int cols = stomp_config_.num_timesteps;
149  header.replace(header.find("@iterations"),std::string("@iterations").length(),std::to_string(total_iterations));
150  header.replace(header.find("@timesteps"),std::string("@timesteps").length(),std::to_string(stomp_config_.num_timesteps));
151  header.replace(header.find("@dimensions"),std::string("@dimensions").length(),std::to_string(stomp_config_.num_dimensions));
152  header.replace(header.find("@rows"),std::string("@rows").length(),std::to_string(rows));
153  header.replace(header.find("@cols"),std::string("@cols").length(),std::to_string(cols));
154 
155  // writing to file stream
156  file_stream_<<header<<std::endl;
157  file_stream_<<stream_.str();
158  file_stream_.close();
159 
160  // clear
161  stream_.str("");
162 
163  ROS_INFO("Saved update log file %s, read with 'numpy.loadtxt(\"%s\")'",full_file_name_.c_str(),filename_.c_str());
164 }
165 
166 } /* namespace smoothers */
167 } /* namespace stomp_moveit */
This defines a update trajectory logger which writes the data to a file.
virtual bool configure(const XmlRpc::XmlRpcValue &config) override
see base class for documentation
virtual bool filter(std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, const Eigen::MatrixXd &parameters, Eigen::MatrixXd &updates, bool &filtered) override
Store the updates values into a file that can be loaded into a numpy array.
virtual bool configure(const XmlRpc::XmlRpcValue &config)
see base class for documentation
Interface class which applies filtering methods to the update parameters before it is added onto the ...
PLUGINLIB_EXPORT_CLASS(test_moveit_controller_manager::TestMoveItControllerManager, moveit_controller_manager::MoveItControllerManager)
virtual bool setMotionPlanRequest(const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::MotionPlanRequest &req, const stomp_core::StompConfiguration &config, moveit_msgs::MoveItErrorCodes &error_code)
see base class for documentation
#define ROS_INFO(...)
virtual bool initialize(moveit::core::RobotModelConstPtr robot_model_ptr, const std::string &group_name, const XmlRpc::XmlRpcValue &config)
see base class for documentation
ROSLIB_DECL std::string getPath(const std::string &package_name)
bool hasMember(const std::string &name) const
Saves the update values into a file for post analysis. The file is compatible with the python numpy l...
Definition: update_logger.h:47
virtual void done(bool success, int total_iterations, double final_cost, const Eigen::MatrixXd &parameters) override
Called by the Stomp at the end of the optimization process.
#define ROS_ERROR(...)


stomp_moveit
Author(s): Jorge Nicho
autogenerated on Fri May 8 2020 03:35:47