44 #include <moveit_servo_lib_parameters.hpp>
51 #include <pluginlib/class_loader.hpp>
52 #include <sensor_msgs/msg/joint_state.hpp>
53 #include <tf2_eigen/tf2_eigen.hpp>
54 #include <tf2_ros/transform_listener.h>
56 #include <rclcpp/logger.hpp>
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_;
void setCommandType(const CommandType &command_type)
Set the type of incoming servo command.
CommandType getCommandType() const
Get the type of command that servo is currently expecting.
KinematicState getCurrentRobotState(bool block_for_current_state) const
Get the current state of the robot as given by planning scene monitor. This may block if a current ro...
Servo(const Servo &)=delete
std::string getStatusMessage() const
Get the message associated with the current servo status.
std::pair< bool, KinematicState > smoothHalt(const KinematicState &halt_state)
Smoothly halt at a commanded state when command goes stale.
Servo & operator=(Servo &)=delete
StatusCode getStatus() const
Get the current status of servo.
servo::Params & getParams()
Returns the most recent servo parameters.
void resetSmoothing(const KinematicState &state)
Resets the smoothing plugin, if set, to a specified state.
Servo(const rclcpp::Node::SharedPtr &node, std::shared_ptr< const servo::ParamListener > servo_param_listener, const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor)
void setCollisionChecking(const bool check_collision)
Start/Stop collision checking thread.
KinematicState getNextJointState(const moveit::core::RobotStatePtr &robot_state, const ServoInput &command)
Computes the joint state required to follow the given command.
void doSmoothing(KinematicState &state)
Applies smoothing to an input state, if a smoothing plugin is set.
std::variant< JointJogCommand, TwistCommand, PoseCommand > ServoInput