42 #include <condition_variable>
48 #include <control_msgs/msg/joint_jog.hpp>
49 #include <geometry_msgs/msg/twist_stamped.hpp>
52 #include <moveit_msgs/srv/change_drift_dimensions.hpp>
53 #include <moveit_msgs/srv/change_control_dimensions.hpp>
54 #include <pluginlib/class_loader.hpp>
55 #include <rclcpp/rclcpp.hpp>
56 #include <sensor_msgs/msg/joint_state.hpp>
57 #include <std_msgs/msg/float64.hpp>
58 #include <std_msgs/msg/float64_multi_array.hpp>
59 #include <std_msgs/msg/int8.hpp>
60 #include <std_srvs/srv/empty.hpp>
61 #include <trajectory_msgs/msg/joint_trajectory.hpp>
82 ServoCalcs(
const rclcpp::Node::SharedPtr& node,
83 const std::shared_ptr<const moveit_servo::ServoParameters>& parameters,
126 trajectory_msgs::msg::JointTrajectory& joint_trajectory);
129 bool jointServoCalcs(
const control_msgs::msg::JointJog& cmd, trajectory_msgs::msg::JointTrajectory& joint_trajectory);
162 void filteredHalt(trajectory_msgs::msg::JointTrajectory& joint_trajectory);
167 void suddenHalt(sensor_msgs::msg::JointState& joint_state,
168 const std::vector<const moveit::core::JointModel*>& joints_to_halt)
const;
173 std::vector<const moveit::core::JointModel*>
enforcePositionLimits(sensor_msgs::msg::JointState& joint_state)
const;
177 trajectory_msgs::msg::JointTrajectory& joint_trajectory);
188 bool internalServoUpdate(Eigen::ArrayXd& delta_theta, trajectory_msgs::msg::JointTrajectory& joint_trajectory,
198 bool applyJointUpdate(
const Eigen::ArrayXd& delta_theta, sensor_msgs::msg::JointState& joint_state);
212 void removeDimension(Eigen::MatrixXd& matrix, Eigen::VectorXd& delta_x,
unsigned int row_to_remove)
const;
233 void twistStampedCB(
const geometry_msgs::msg::TwistStamped::ConstSharedPtr& msg);
234 void jointCmdCB(
const control_msgs::msg::JointJog::ConstSharedPtr& msg);
245 void changeDriftDimensions(
const std::shared_ptr<moveit_msgs::srv::ChangeDriftDimensions::Request>& req,
246 const std::shared_ptr<moveit_msgs::srv::ChangeDriftDimensions::Response>& res);
251 const std::shared_ptr<moveit_msgs::srv::ChangeControlDimensions::Response>& res);
254 bool resetServoStatus(
const std::shared_ptr<std_srvs::srv::Empty::Request>& req,
255 const std::shared_ptr<std_srvs::srv::Empty::Response>& res);
258 std::shared_ptr<rclcpp::Node>
node_;
261 const std::shared_ptr<const moveit_servo::ServoParameters>
parameters_;
297 std::shared_ptr<online_signal_smoothing::SmoothingBaseClass>
smoother_;
const std::shared_ptr< const moveit_servo::ServoParameters > parameters_
bool latest_joint_cmd_is_nonzero_
bool have_nonzero_joint_command_
std::atomic< bool > paused_
void removeDimension(Eigen::MatrixXd &matrix, Eigen::VectorXd &delta_x, unsigned int row_to_remove) const
rclcpp::Publisher< std_msgs::msg::Int8 >::SharedPtr status_pub_
Eigen::Isometry3d tf_moveit_to_ee_frame_
std::array< bool, 6 > control_dimensions_
std::array< bool, 6 > drift_dimensions_
void changeDriftDimensions(const std::shared_ptr< moveit_msgs::srv::ChangeDriftDimensions::Request > &req, const std::shared_ptr< moveit_msgs::srv::ChangeDriftDimensions::Response > &res)
moveit::core::RobotStatePtr current_state_
void resetLowPassFilters(const sensor_msgs::msg::JointState &joint_state)
Set the filters to the specified values.
sensor_msgs::msg::JointState original_joint_state_
void updateJoints()
Parse the incoming joint msg for the joints of our MoveGroup.
control_msgs::msg::JointJog joint_servo_cmd_
void insertRedundantPointsIntoTrajectory(trajectory_msgs::msg::JointTrajectory &joint_trajectory, int count) const
Gazebo simulations have very strict message timestamp requirements. Satisfy Gazebo by stuffing multip...
void setPaused(bool paused)
Pause or unpause processing servo commands while keeping the timers alive.
rclcpp::Service< moveit_msgs::srv::ChangeControlDimensions >::SharedPtr control_dimensions_server_
Eigen::Isometry3d tf_moveit_to_robot_cmd_frame_
rclcpp::Service< moveit_msgs::srv::ChangeDriftDimensions >::SharedPtr drift_dimensions_server_
std::string robot_link_command_frame_
const int gazebo_redundant_message_count_
rclcpp::Publisher< std_msgs::msg::Float64MultiArray >::SharedPtr multiarray_outgoing_cmd_pub_
bool latest_twist_cmd_is_nonzero_
std::map< std::string, std::size_t > joint_state_name_map_
bool jointServoCalcs(const control_msgs::msg::JointJog &cmd, trajectory_msgs::msg::JointTrajectory &joint_trajectory)
Do servoing calculations for direct commands to a joint.
void stop()
Stop the currently running thread.
double collision_velocity_scale_
bool cartesianServoCalcs(geometry_msgs::msg::TwistStamped &cmd, trajectory_msgs::msg::JointTrajectory &joint_trajectory)
Do servoing calculations for Cartesian twist commands.
pluginlib::ClassLoader< online_signal_smoothing::SmoothingBaseClass > smoothing_loader_
rclcpp::Service< std_srvs::srv::Empty >::SharedPtr reset_servo_status_
bool twist_command_is_stale_
rclcpp::Subscription< geometry_msgs::msg::TwistStamped >::SharedPtr twist_stamped_sub_
void jointStateCB(const sensor_msgs::msg::JointState::SharedPtr msg)
control_msgs::msg::JointJog::ConstSharedPtr latest_joint_cmd_
rclcpp::Subscription< sensor_msgs::msg::JointState >::SharedPtr joint_state_sub_
geometry_msgs::msg::TwistStamped::ConstSharedPtr latest_twist_stamped_
bool joint_command_is_stale_
geometry_msgs::msg::TwistStamped twist_stamped_cmd_
rclcpp::Subscription< control_msgs::msg::JointJog >::SharedPtr joint_cmd_sub_
std::condition_variable input_cv_
Eigen::ArrayXd delta_theta_
sensor_msgs::msg::JointState internal_joint_state_
rclcpp::Subscription< std_msgs::msg::Float64 >::SharedPtr collision_velocity_scale_sub_
void changeControlDimensions(const std::shared_ptr< moveit_msgs::srv::ChangeControlDimensions::Request > &req, const std::shared_ptr< moveit_msgs::srv::ChangeControlDimensions::Response > &res)
Start the main calculation timer.
bool getEEFrameTransform(Eigen::Isometry3d &transform)
bool wait_for_servo_commands_
void collisionVelocityScaleCB(const std_msgs::msg::Float64::ConstSharedPtr &msg)
void twistStampedCB(const geometry_msgs::msg::TwistStamped::ConstSharedPtr &msg)
Eigen::VectorXd scaleJointCommand(const control_msgs::msg::JointJog &command)
If incoming velocity commands are from a unitless joystick, scale them to physical units....
bool internalServoUpdate(Eigen::ArrayXd &delta_theta, trajectory_msgs::msg::JointTrajectory &joint_trajectory, const ServoType servo_type)
Handles all aspects of the servoing after the desired joint commands are established Joint and Cartes...
rclcpp::Time latest_joint_command_stamp_
rcl_interfaces::msg::SetParametersResult robotLinkCommandFrameCallback(const rclcpp::Parameter ¶meter)
void mainCalcLoop()
Run the main calculation loop.
bool have_nonzero_command_
void calculateSingleIteration()
Do calculations for a single iteration. Publish one outgoing command.
void jointCmdCB(const control_msgs::msg::JointJog::ConstSharedPtr &msg)
rclcpp::Time latest_twist_command_stamp_
const moveit::core::JointModelGroup * joint_model_group_
rclcpp::Publisher< trajectory_msgs::msg::JointTrajectory >::SharedPtr trajectory_outgoing_cmd_pub_
std::mutex main_loop_mutex_
trajectory_msgs::msg::JointTrajectory::SharedPtr last_sent_command_
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
bool checkValidCommand(const control_msgs::msg::JointJog &cmd)
void composeJointTrajMessage(const sensor_msgs::msg::JointState &joint_state, trajectory_msgs::msg::JointTrajectory &joint_trajectory)
Compose the outgoing JointTrajectory message.
bool getCommandFrameTransform(Eigen::Isometry3d &transform)
void suddenHalt(sensor_msgs::msg::JointState &joint_state, const std::vector< const moveit::core::JointModel * > &joints_to_halt) const
Suddenly halt for a joint limit or other critical issue. Is handled differently for position vs....
std::shared_ptr< online_signal_smoothing::SmoothingBaseClass > smoother_
void filteredHalt(trajectory_msgs::msg::JointTrajectory &joint_trajectory)
Come to a halt in a smooth way. Apply a smoothing plugin, if one is configured.
void start()
Start the timer where we do work and publish outputs.
bool have_nonzero_twist_stamped_
Eigen::VectorXd scaleCartesianCommand(const geometry_msgs::msg::TwistStamped &command)
If incoming velocity commands are from a unitless joystick, scale them to physical units....
Eigen::Isometry3d ik_base_to_tip_frame_
void enforceControlDimensions(geometry_msgs::msg::TwistStamped &command)
void removeDriftDimensions(Eigen::MatrixXd &matrix, Eigen::VectorXd &delta_x)
bool resetServoStatus(const std::shared_ptr< std_srvs::srv::Empty::Request > &req, const std::shared_ptr< std_srvs::srv::Empty::Response > &res)
Service callback to reset Servo status, e.g. so the arm can move again after a collision.
std::shared_ptr< rclcpp::Node > node_
kinematics::KinematicsBaseConstPtr ik_solver_
bool applyJointUpdate(const Eigen::ArrayXd &delta_theta, sensor_msgs::msg::JointState &joint_state)
Joint-wise update of a sensor_msgs::msg::JointState with given delta's Also filters and calculates th...
ServoCalcs(const rclcpp::Node::SharedPtr &node, const std::shared_ptr< const moveit_servo::ServoParameters > ¶meters, const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor)
std::atomic< bool > done_stopping_
std::vector< const moveit::core::JointModel * > enforcePositionLimits(sensor_msgs::msg::JointState &joint_state) const
Avoid overshooting joint limits.