65 Servo(
const rclcpp::Node::SharedPtr& node, std::shared_ptr<const servo::ParamListener> servo_param_listener,
158 std::optional<Eigen::Isometry3d> getPlanningToCommandFrameTransform(
const std::string& command_frame,
159 const std::string& planning_frame)
const;
171 std::optional<TwistCommand> toPlanningFrame(
const TwistCommand& command,
const std::string& planning_frame)
const;
179 std::optional<PoseCommand> toPlanningFrame(
const PoseCommand& command,
const std::string& planning_frame)
const;
187 Eigen::VectorXd jointDeltaFromCommand(
const ServoInput& command,
const moveit::core::RobotStatePtr& robot_state);
194 bool validateParams(
const servo::Params& servo_params);
204 void setSmoothingPlugin();
220 std::atomic<CommandType> expected_command_type_;
222 servo::Params servo_params_;
223 const rclcpp::Node::SharedPtr node_;
224 rclcpp::Logger logger_;
225 std::shared_ptr<const servo::ParamListener> servo_param_listener_;
226 planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
229 std::atomic<double> collision_velocity_scale_ = 1.0;
230 std::unique_ptr<CollisionMonitor> collision_monitor_;
233 pluginlib::UniquePtr<online_signal_smoothing::SmoothingBaseClass> smoother_ =
nullptr;
236 std::unordered_map<std::string, JointNameToMoveGroupIndexMap> joint_name_to_index_maps_;
239 std::vector<double> joint_limit_margins_;