65 Servo(
const rclcpp::Node::SharedPtr& node, std::shared_ptr<const servo::ParamListener> servo_param_listener,
156 std::optional<Eigen::Isometry3d> getPlanningToCommandFrameTransform(
const std::string& command_frame,
157 const std::string& planning_frame)
const;
169 std::optional<TwistCommand> toPlanningFrame(
const TwistCommand& command,
const std::string& planning_frame)
const;
177 std::optional<PoseCommand> toPlanningFrame(
const PoseCommand& command,
const std::string& planning_frame)
const;
185 Eigen::VectorXd jointDeltaFromCommand(
const ServoInput& command,
const moveit::core::RobotStatePtr& robot_state);
192 bool validateParams(
const servo::Params& servo_params);
202 void setSmoothingPlugin();
218 std::atomic<CommandType> expected_command_type_;
220 servo::Params servo_params_;
221 const rclcpp::Node::SharedPtr node_;
222 rclcpp::Logger logger_;
223 std::shared_ptr<const servo::ParamListener> servo_param_listener_;
224 planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
227 std::atomic<double> collision_velocity_scale_ = 1.0;
228 std::unique_ptr<CollisionMonitor> collision_monitor_;
231 pluginlib::UniquePtr<online_signal_smoothing::SmoothingBaseClass> smoother_ =
nullptr;
234 std::unordered_map<std::string, JointNameToMoveGroupIndexMap> joint_name_to_index_maps_;
237 std::vector<double> joint_limit_margins_;