@@ -44,8 +44,8 @@ constexpr char LOGNAME[] = "action_base";
4444
4545ActionBase::ActionBase (const std::string& action_name, bool spin_thread, double goal_timeout, double server_timeout)
4646 : action_name_(action_name), server_timeout_(server_timeout), goal_timeout_(goal_timeout) {
47- clientPtr_. reset (
48- new actionlib::SimpleActionClient<grasping_msgs::GraspPlanningAction>(nh_, action_name_, spin_thread) );
47+ clientPtr_ = std::make_unique<actionlib::SimpleActionClient<grasping_msgs::GraspPlanningAction>>(nh_, action_name_,
48+ spin_thread);
4949
5050 // Negative timeouts are set to zero
5151 server_timeout_ = server_timeout_ < std::numeric_limits<double >::epsilon () ? 0.0 : server_timeout_;
@@ -57,14 +57,7 @@ ActionBase::ActionBase(const std::string& action_name, bool spin_thread, double
5757}
5858
5959ActionBase::ActionBase (const std::string& action_name, bool spin_thread)
60- : action_name_(action_name), server_timeout_(0.0 ), goal_timeout_(0.0 ) {
61- clientPtr_.reset (
62- new actionlib::SimpleActionClient<grasping_msgs::GraspPlanningAction>(nh_, action_name_, spin_thread));
63-
64- ROS_DEBUG_STREAM_NAMED (LOGNAME, " Waiting for connection to grasp generation action server..." );
65- clientPtr_->waitForServer (ros::Duration (server_timeout_));
66- ROS_DEBUG_STREAM_NAMED (LOGNAME, " Connected to server" );
67- }
60+ : ActionBase::ActionBase(action_name, spin_thread, 0.0 , 0.0 ) {}
6861} // namespace stages
6962} // namespace task_constructor
7063} // namespace moveit
0 commit comments