47 const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit_servo.servo");
48 constexpr
double ROBOT_STATE_WAIT_TIME = 10.0;
54 , parameters_{ parameters }
55 , servo_calcs_{ node, parameters, planning_scene_monitor_ }
56 , collision_checker_{ node, parameters, planning_scene_monitor_ }
62 if (!planning_scene_monitor_->getStateMonitor()->waitForCompleteState(parameters_->move_group_name,
63 ROBOT_STATE_WAIT_TIME))
65 RCLCPP_ERROR(LOGGER,
"Timeout waiting for current state");
75 if (parameters_->check_collisions)
76 collision_checker_.
start();
void setPaused(bool paused)
Pause or unpause processing servo commands while keeping the timers alive.
void start()
start the Timer that regulates collision check rate
void setPaused(bool paused)
Pause or unpause processing servo commands while keeping the timers alive.
bool getEEFrameTransform(Eigen::Isometry3d &transform)
bool getCommandFrameTransform(Eigen::Isometry3d &transform)
void start()
Start the timer where we do work and publish outputs.
void setPaused(bool paused)
Pause or unpause processing servo commands while keeping the timers alive.
const ServoParameters::SharedConstPtr & getParameters() const
Get the parameters used by servo node.
bool getEEFrameTransform(Eigen::Isometry3d &transform)
void start()
start servo node
Servo(const rclcpp::Node::SharedPtr &node, const ServoParameters::SharedConstPtr ¶meters, const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor)
bool getCommandFrameTransform(Eigen::Isometry3d &transform)
const rclcpp::Logger LOGGER
std::shared_ptr< const ServoParameters > SharedConstPtr