38 #include <dynamic_reconfigure/server.h>
39 #include <moveit_ros_manipulation/PickPlaceDynamicReconfigureConfig.h>
45 using namespace moveit_ros_manipulation;
47 class DynamicReconfigureImpl
53 [
this](
auto& config, uint32_t level) { dynamicReconfigureCallback(config, level); });
56 const PickPlaceParams& getParams()
const
64 void dynamicReconfigureCallback(PickPlaceDynamicReconfigureConfig& config, uint32_t )
66 params_.max_goal_count_ = config.max_attempted_states_per_pose;
67 params_.max_fail_ = config.max_consecutive_fail_attempts;
68 params_.max_step_ = config.cartesian_motion_step_size;
69 params_.jump_factor_ = config.jump_factor;
83 static DynamicReconfigureImpl pick_place_params;
84 return pick_place_params.getParams();