moveit::planning_interface::MoveGroupInterface Class Reference
http://docs.ros.org/en/melodic/api/moveit_ros_planning_interface/html/classmoveit_1_1planning__interface_1_1MoveGroupInterface.html
#include <moveit/planning_interface/move_group_interface.h>
class moveit::planning_interface::MoveGroupInterface
moveit::core::MoveItErrorCode moveit::planning_interface::MoveGroupInterface::move()
{
return impl_->move(true);
}
class moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl
moveit::core::MoveItErrorCode move(bool wait)
{
略
move_action_client_->sendGoal(goal);
if (!wait)
{
return moveit::core::MoveItErrorCode::SUCCESS;
}
if (!move_action_client_->waitForResult())
{
ROS_INFO_STREAM_NAMED("move_group_interface", "MoveGroup action returned early");
}
if (move_action_client_->getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
{
return move_action_client_->getResult()->error_code;
}
else
{
ROS_INFO_STREAM_NAMED("move_group_interface", move_action_client_->getState().toString()
<< ": " << move_action_client_->getState().getText());
return move_action_client_->getResult()->error_code;
}
}
namespace moveit
{
namespace planning_interface
{
class MoveGroupInterface
{
private:
class MoveGroupInterfaceImpl;
MoveGroupInterfaceImpl* impl_;
};
} // namespace planning_interface
} // namespace moveit