Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <moveit/pick_place/pick_place_params.h>
00038 #include <dynamic_reconfigure/server.h>
00039 #include <moveit_ros_manipulation/PickPlaceDynamicReconfigureConfig.h>
00040
00041 namespace pick_place
00042 {
00043 namespace
00044 {
00045 using namespace moveit_ros_manipulation;
00046
00047 class DynamicReconfigureImpl
00048 {
00049 public:
00050 DynamicReconfigureImpl() : dynamic_reconfigure_server_(ros::NodeHandle("~/pick_place"))
00051 {
00052 dynamic_reconfigure_server_.setCallback(
00053 boost::bind(&DynamicReconfigureImpl::dynamicReconfigureCallback, this, _1, _2));
00054 }
00055
00056 const PickPlaceParams& getParams() const
00057 {
00058 return params_;
00059 }
00060
00061 private:
00062 PickPlaceParams params_;
00063
00064 void dynamicReconfigureCallback(PickPlaceDynamicReconfigureConfig& config, uint32_t level)
00065 {
00066 params_.max_goal_count_ = config.max_attempted_states_per_pose;
00067 params_.max_fail_ = config.max_consecutive_fail_attempts;
00068 params_.max_step_ = config.cartesian_motion_step_size;
00069 params_.jump_factor_ = config.jump_factor;
00070 }
00071
00072 dynamic_reconfigure::Server<PickPlaceDynamicReconfigureConfig> dynamic_reconfigure_server_;
00073 };
00074 }
00075 }
00076
00077 pick_place::PickPlaceParams::PickPlaceParams() : max_goal_count_(5), max_fail_(3), max_step_(0.02), jump_factor_(2.0)
00078 {
00079 }
00080
00081 const pick_place::PickPlaceParams& pick_place::GetGlobalPickPlaceParams()
00082 {
00083 static DynamicReconfigureImpl PICK_PLACE_PARAMS;
00084 return PICK_PLACE_PARAMS.getParams();
00085 }