joint_limits.cpp
Go to the documentation of this file.
00001 
00026 #include <ros/console.h>
00027 #include <pluginlib/class_list_macros.h>
00028 #include <moveit/robot_state/conversions.h>
00029 #include <stomp_moveit/noisy_filters/joint_limits.h>
00030 
00031 PLUGINLIB_EXPORT_CLASS(stomp_moveit::noisy_filters::JointLimits,stomp_moveit::noisy_filters::StompNoisyFilter);
00032 
00033 namespace stomp_moveit
00034 {
00035 namespace noisy_filters
00036 {
00037 
00038 JointLimits::JointLimits():
00039     lock_start_(true),
00040     lock_goal_(true)
00041 {
00042   // TODO Auto-generated constructor stub
00043 
00044 }
00045 
00046 JointLimits::~JointLimits()
00047 {
00048   // TODO Auto-generated destructor stub
00049 }
00050 
00051 bool JointLimits::initialize(moveit::core::RobotModelConstPtr robot_model_ptr,
00052                         const std::string& group_name,const XmlRpc::XmlRpcValue& config)
00053 {
00054   using namespace moveit::core;
00055 
00056   robot_model_ = robot_model_ptr;
00057   group_name_ = group_name;
00058 
00059   // creating states
00060   start_state_.reset(new RobotState(robot_model_));
00061   goal_state_.reset(new RobotState(robot_model_));
00062 
00063   return configure(config);
00064 }
00065 
00066 bool JointLimits::configure(const XmlRpc::XmlRpcValue& config)
00067 {
00068 
00069   // check parameter presence
00070   auto members = {"lock_start","lock_goal"};
00071   for(auto& m : members)
00072   {
00073     if(!config.hasMember(m))
00074     {
00075       ROS_ERROR("%s failed to find one or more required parameters",getName().c_str());
00076       return false;
00077     }
00078   }
00079 
00080   try
00081   {
00082     XmlRpc::XmlRpcValue c = config;
00083     lock_start_ = static_cast<bool>(c["lock_start"]);
00084     lock_goal_ = static_cast<bool>(c["lock_goal"]);
00085   }
00086   catch(XmlRpc::XmlRpcException& e)
00087   {
00088     ROS_ERROR("JointLimits plugin failed to load parameters %s",e.getMessage().c_str());
00089     return false;
00090   }
00091 
00092   return true;
00093 }
00094 
00095 bool JointLimits::setMotionPlanRequest(const planning_scene::PlanningSceneConstPtr& planning_scene,
00096                  const moveit_msgs::MotionPlanRequest &req,
00097                  const stomp_core::StompConfiguration &config,
00098                  moveit_msgs::MoveItErrorCodes& error_code)
00099 {
00100   using namespace moveit::core;
00101 
00102   error_code.val = error_code.val | moveit_msgs::MoveItErrorCodes::SUCCESS;
00103 
00104   // saving start state
00105   if(!robotStateMsgToRobotState(req.start_state,*start_state_))
00106   {
00107     ROS_ERROR_STREAM("Failed to save start state");
00108     return false;
00109   }
00110 
00111   if(!start_state_->satisfiesBounds(robot_model_->getJointModelGroup(group_name_)))
00112   {
00113     ROS_WARN("%s Requested Start State is out of bounds",getName().c_str());
00114   }
00115 
00116   // saving goal state
00117   if(lock_goal_)
00118   {
00119     bool goal_state_saved = false;
00120     for(auto& gc: req.goal_constraints)
00121     {
00122       for(auto& jc : gc.joint_constraints)
00123       {
00124         goal_state_->setVariablePosition(jc.joint_name,jc.position);
00125         goal_state_saved = true;
00126       }
00127 
00128       if(!goal_state_->satisfiesBounds(robot_model_->getJointModelGroup(group_name_)))
00129       {
00130         ROS_WARN("%s Requested Goal State is out of bounds",getName().c_str());
00131       }
00132 
00133       break;
00134     }
00135 
00136     if(!goal_state_saved)
00137     {
00138       ROS_ERROR_STREAM("Failed to save goal state");
00139       return false;
00140     }
00141   }
00142 
00143   return true;
00144 }
00145 
00146 bool JointLimits::filter(std::size_t start_timestep,std::size_t num_timesteps,
00147                          int iteration_number,int rollout_number,Eigen::MatrixXd& parameters,bool& filtered)
00148 {
00149   using namespace moveit::core;
00150 
00151   filtered = false;
00152   const JointModelGroup* joint_group  = robot_model_->getJointModelGroup(group_name_);
00153   const std::vector<const JointModel*>& joint_models = joint_group->getActiveJointModels();
00154   std::size_t num_joints = joint_group->getActiveJointModelNames().size();
00155   if(parameters.rows() != num_joints)
00156   {
00157     ROS_ERROR("Incorrect number of joints in the 'parameters' matrix");
00158     return false;
00159   }
00160 
00161   if(lock_start_)
00162   {
00163     for(auto j = 0u; j < num_joints; j++)
00164     {
00165       parameters(j,0) =  *start_state_->getJointPositions(joint_models[j]);
00166     }
00167 
00168     filtered = true;
00169   }
00170 
00171   if(lock_goal_)
00172   {
00173     auto last_index = parameters.cols()-1;
00174     for(auto j = 0u; j < num_joints; j++)
00175     {
00176       parameters(j,last_index) =  *goal_state_->getJointPositions(joint_models[j]);
00177     }
00178 
00179     filtered = true;
00180   }
00181 
00182   double val;
00183   for (auto j = 0u; j < num_joints; ++j)
00184   {
00185     for (auto t=0u; t< parameters.cols(); ++t)
00186     {
00187       val = parameters(j,t);
00188       if(joint_models[j]->enforcePositionBounds(&val))
00189       {
00190         parameters(j,t) = val;
00191         filtered = true;
00192       }
00193     }
00194   }
00195 
00196   return true;
00197 }
00198 
00199 } /* namespace filters */
00200 } /* namespace stomp_moveit */


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