normal_distribution_sampling.cpp
Go to the documentation of this file.
00001 
00026 #include <stomp_moveit/noise_generators/normal_distribution_sampling.h>
00027 #include <stomp_moveit/utils/multivariate_gaussian.h>
00028 #include <XmlRpcException.h>
00029 #include <pluginlib/class_list_macros.h>
00030 #include <ros/console.h>
00031 
00032 PLUGINLIB_EXPORT_CLASS(stomp_moveit::noise_generators::NormalDistributionSampling,stomp_moveit::noise_generators::StompNoiseGenerator);
00033 
00034 /*
00035  * These coefficients correspond to the five point stencil method
00036  */
00037 static const std::vector<double> ACC_MATRIX_DIAGONAL_VALUES = {-1.0/12.0, 16.0/12.0, -30.0/12.0, 16.0/12.0, -1.0/12.0};
00038 static const std::vector<int> ACC_MATRIX_DIAGONAL_INDICES = {-2, -1, 0 ,1, 2};
00039 
00040 namespace stomp_moveit
00041 {
00042 
00043 namespace noise_generators
00044 {
00045 
00046 NormalDistributionSampling::NormalDistributionSampling():
00047     name_("NormalDistributionSampling")
00048 {
00049   // TODO Auto-generated constructor stub
00050 
00051 }
00052 
00053 NormalDistributionSampling::~NormalDistributionSampling()
00054 
00055 {
00056   // TODO Auto-generated destructor stub
00057 }
00058 
00059 bool NormalDistributionSampling::initialize(moveit::core::RobotModelConstPtr robot_model_ptr,
00060                         const std::string& group_name,const XmlRpc::XmlRpcValue& config)
00061 {
00062   using namespace moveit::core;
00063 
00064   group_ = group_name;
00065   const JointModelGroup* joint_group = robot_model_ptr->getJointModelGroup(group_name);
00066   if(!joint_group)
00067   {
00068     ROS_ERROR("Invalid joint group %s",group_name.c_str());
00069     return false;
00070   }
00071 
00072   stddev_.resize(joint_group->getActiveJointModelNames().size());
00073 
00074 
00075   return configure(config);
00076 }
00077 
00078 bool NormalDistributionSampling::configure(const XmlRpc::XmlRpcValue& config)
00079 {
00080   using namespace XmlRpc;
00081 
00082   try
00083   {
00084     XmlRpcValue c = config;
00085     XmlRpcValue stddev_param = c["stddev"];
00086 
00087     if(stddev_param.size() < stddev_.size())
00088     {
00089       ROS_ERROR("%s the 'stddev' parameter has fewer elements than the number of joints",getName().c_str());
00090       return false;
00091     }
00092 
00093     stddev_.resize(stddev_param.size());
00094     for(auto i = 0u; i < stddev_param.size(); i++)
00095     {
00096       stddev_[i] = static_cast<double>(stddev_param[i]);
00097     }
00098   }
00099   catch(XmlRpc::XmlRpcException& e)
00100   {
00101     ROS_ERROR("%s failed to load parameters",getName().c_str());
00102     return false;
00103   }
00104 
00105   return true;
00106 }
00107 
00108 bool NormalDistributionSampling::setMotionPlanRequest(const planning_scene::PlanningSceneConstPtr& planning_scene,
00109                  const moveit_msgs::MotionPlanRequest &req,
00110                  const stomp_core::StompConfiguration &config,
00111                  moveit_msgs::MoveItErrorCodes& error_code)
00112 {
00113   using namespace Eigen;
00114 
00115   auto fill_diagonal = [](Eigen::MatrixXd& m,double coeff,int diag_index)
00116   {
00117     std::size_t size = m.rows() - std::abs(diag_index);
00118     m.diagonal(diag_index) = VectorXd::Constant(size,coeff);
00119   };
00120 
00121   // creating finite difference acceleration matrix
00122   std::size_t num_timesteps = config.num_timesteps;
00123   Eigen::MatrixXd A = MatrixXd::Zero(num_timesteps,num_timesteps);
00124   int num_elements = (int((ACC_MATRIX_DIAGONAL_INDICES.size() -1)/2.0) + 1)* num_timesteps ;
00125   for(auto i = 0u; i < ACC_MATRIX_DIAGONAL_INDICES.size() ; i++)
00126   {
00127     fill_diagonal(A,ACC_MATRIX_DIAGONAL_VALUES[i],ACC_MATRIX_DIAGONAL_INDICES[i]);
00128   }
00129 
00130   // create and scale covariance matrix
00131   Eigen::MatrixXd covariance = MatrixXd::Identity(num_timesteps,num_timesteps);
00132   covariance = A.transpose() * A;
00133   covariance = covariance.fullPivLu().inverse();
00134   double max_val = covariance.array().abs().matrix().maxCoeff();
00135   covariance /= max_val;
00136 
00137   // create random generators
00138   rand_generators_.resize(stddev_.size());
00139   for(auto& r: rand_generators_)
00140   {
00141     r.reset(new utils::MultivariateGaussian(VectorXd::Zero(num_timesteps),covariance));
00142   }
00143 
00144   // preallocating noise data
00145   raw_noise_.resize(config.num_timesteps);
00146   raw_noise_.setZero();
00147 
00148   return true;
00149 }
00150 
00151 
00152 bool NormalDistributionSampling::generateNoise(const Eigen::MatrixXd& parameters,
00153                                      std::size_t start_timestep,
00154                                      std::size_t num_timesteps,
00155                                      int iteration_number,
00156                                      int rollout_number,
00157                                      Eigen::MatrixXd& parameters_noise,
00158                                      Eigen::MatrixXd& noise)
00159 {
00160   if(parameters.rows() != stddev_.size())
00161   {
00162     ROS_ERROR("Number of parameters %i differs from what was preallocated ",int(parameters.rows()));
00163     return false;
00164   }
00165 
00166 
00167   for(auto d = 0u; d < parameters.rows() ; d++)
00168   {
00169     rand_generators_[d]->sample(raw_noise_);
00170     noise.row(d).transpose() = stddev_[d] * raw_noise_;
00171     parameters_noise.row(d) = parameters.row(d) + noise.row(d);
00172   }
00173 
00174   return true;
00175 }
00176 
00177 } /* namespace noise_generators */
00178 } /* namespace stomp_moveit */


stomp_moveit
Author(s): Jorge Nicho
autogenerated on Sat Jun 8 2019 19:24:01