Go to the documentation of this file.
42 #include <condition_variable>
48 #include <control_msgs/JointJog.h>
49 #include <geometry_msgs/TwistStamped.h>
50 #include <geometry_msgs/TransformStamped.h>
53 #include <moveit_msgs/ChangeDriftDimensions.h>
54 #include <moveit_msgs/ChangeControlDimensions.h>
55 #include <sensor_msgs/JointState.h>
56 #include <std_msgs/Float64.h>
57 #include <std_msgs/Int8.h>
58 #include <std_srvs/Empty.h>
60 #include <trajectory_msgs/JointTrajectory.h>
122 bool cartesianServoCalcs(geometry_msgs::TwistStamped& cmd, trajectory_msgs::JointTrajectory& joint_trajectory);
125 bool jointServoCalcs(
const control_msgs::JointJog& cmd, trajectory_msgs::JointTrajectory& joint_trajectory);
140 bool addJointIncrements(sensor_msgs::JointState& output,
const Eigen::VectorXd& increments)
const;
145 void suddenHalt(trajectory_msgs::JointTrajectory& joint_trajectory);
157 const Eigen::JacobiSVD<Eigen::MatrixXd>& svd,
158 const Eigen::MatrixXd& pseudo_inverse);
169 trajectory_msgs::JointTrajectory& joint_trajectory)
const;
197 void removeDimension(Eigen::MatrixXd& matrix, Eigen::VectorXd& delta_x,
unsigned int row_to_remove);
200 void jointStateCB(
const sensor_msgs::JointStateConstPtr& msg);
203 void twistStampedCB(
const geometry_msgs::TwistStampedConstPtr& msg);
204 void jointCmdCB(
const control_msgs::JointJogConstPtr& msg);
216 moveit_msgs::ChangeDriftDimensions::Response& res);
220 moveit_msgs::ChangeControlDimensions::Response& res);
223 bool resetServoStatus(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res);
301 std::array<bool, 6>
drift_dimensions_ = { {
false,
false,
false,
false,
false,
false } };
ros::Subscriber collision_velocity_scale_sub_
void changeRobotLinkCommandFrame(const std::string &new_command_frame)
Change the controlled link. Often, this is the end effector This must be a link on the robot since Mo...
control_msgs::JointJogConstPtr latest_joint_cmd_
void jointCmdCB(const control_msgs::JointJogConstPtr &msg)
sensor_msgs::JointState internal_joint_state_
std::map< std::string, std::size_t > joint_state_name_map_
void collisionVelocityScaleCB(const std_msgs::Float64ConstPtr &msg)
bool wait_for_servo_commands_
void stop()
Stop the currently running thread.
bool addJointIncrements(sensor_msgs::JointState &output, const Eigen::VectorXd &increments) const
ros::Subscriber joint_cmd_sub_
void calculateJointVelocities(sensor_msgs::JointState &joint_state, const Eigen::ArrayXd &delta_theta)
Convert an incremental position command to joint velocity message.
ros::Publisher status_pub_
ros::ServiceServer control_dimensions_server_
Eigen::Isometry3d tf_moveit_to_ee_frame_
void twistStampedCB(const geometry_msgs::TwistStampedConstPtr &msg)
bool cartesianServoCalcs(geometry_msgs::TwistStamped &cmd, trajectory_msgs::JointTrajectory &joint_trajectory)
Do servoing calculations for Cartesian twist commands.
std::array< bool, 6 > drift_dimensions_
bool have_nonzero_command_
ServoCalcs(ros::NodeHandle &nh, ServoParameters ¶meters, const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor)
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
void suddenHalt(trajectory_msgs::JointTrajectory &joint_trajectory)
Suddenly halt for a joint limit or other critical issue. Is handled differently for position vs....
void composeJointTrajMessage(const sensor_msgs::JointState &joint_state, trajectory_msgs::JointTrajectory &joint_trajectory) const
Compose the outgoing JointTrajectory message.
friend class ServoFixture
double collision_velocity_scale_
bool getCommandFrameTransform(Eigen::Isometry3d &transform)
void removeDimension(Eigen::MatrixXd &matrix, Eigen::VectorXd &delta_x, unsigned int row_to_remove)
ros::Time latest_joint_command_stamp_
sensor_msgs::JointState original_joint_state_
bool convertDeltasToOutgoingCmd(trajectory_msgs::JointTrajectory &joint_trajectory)
Convert joint deltas to an outgoing JointTrajectory command. This happens for joint commands and Cart...
std::vector< LowPassFilter > position_filters_
moveit::core::RobotStatePtr current_state_
ros::Publisher worst_case_stop_time_pub_
void jointStateCB(const sensor_msgs::JointStateConstPtr &msg)
bool latest_nonzero_twist_stamped_
void updateJoints()
Parse the incoming joint msg for the joints of our MoveGroup.
void lowPassFilterPositions(sensor_msgs::JointState &joint_state)
Smooth position commands with a lowpass filter.
Eigen::ArrayXd delta_theta_
bool joint_command_is_stale_
geometry_msgs::TwistStampedConstPtr latest_twist_stamped_
ServoParameters & parameters_
bool changeDriftDimensions(moveit_msgs::ChangeDriftDimensions::Request &req, moveit_msgs::ChangeDriftDimensions::Response &res)
std::atomic< bool > paused_
bool changeControlDimensions(moveit_msgs::ChangeControlDimensions::Request &req, moveit_msgs::ChangeControlDimensions::Response &res)
Service callback for changing servoing dimensions (e.g. ignore rotation about X)
const int gazebo_redundant_message_count_
bool getEEFrameTransform(Eigen::Isometry3d &transform)
ros::ServiceServer reset_servo_status_
void setPaused(bool paused)
Pause or unpause processing servo commands while keeping the timers alive.
ros::ServiceServer drift_dimensions_server_
void resetLowPassFilters(const sensor_msgs::JointState &joint_state)
Set the filters to the specified values.
bool resetServoStatus(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Service callback to reset Servo status, e.g. so the arm can move again after a collision.
void enforceVelLimits(Eigen::ArrayXd &delta_theta)
Scale the delta theta to match joint velocity/acceleration limits.
bool have_nonzero_joint_command_
const moveit::core::JointModelGroup * joint_model_group_
void insertRedundantPointsIntoTrajectory(trajectory_msgs::JointTrajectory &joint_trajectory, int count) const
Gazebo simulations have very strict message timestamp requirements. Satisfy Gazebo by stuffing multip...
double velocityScalingFactorForSingularity(const Eigen::VectorXd &commanded_velocity, const Eigen::JacobiSVD< Eigen::MatrixXd > &svd, const Eigen::MatrixXd &pseudo_inverse)
Possibly calculate a velocity scaling factor, due to proximity of singularity and direction of motion...
bool enforcePositionLimits(sensor_msgs::JointState &joint_state)
Avoid overshooting joint limits.
bool have_nonzero_twist_stamped_
std::condition_variable input_cv_
ros::Subscriber joint_state_sub_
ros::Publisher outgoing_cmd_pub_
trajectory_msgs::JointTrajectoryConstPtr last_sent_command_
void applyVelocityScaling(Eigen::ArrayXd &delta_theta, double singularity_scale)
ros::Time latest_twist_command_stamp_
Eigen::VectorXd scaleJointCommand(const control_msgs::JointJog &command) const
If incoming velocity commands are from a unitless joystick, scale them to physical units....
void start()
Start the timer where we do work and publish outputs.
Eigen::ArrayXd prev_joint_velocity_
Eigen::VectorXd scaleCartesianCommand(const geometry_msgs::TwistStamped &command) const
If incoming velocity commands are from a unitless joystick, scale them to physical units....
void mainCalcLoop()
Run the main calculation loop.
void calculateSingleIteration()
Do calculations for a single iteration. Publish one outgoing command.
bool latest_nonzero_joint_cmd_
Eigen::Isometry3d tf_moveit_to_robot_cmd_frame_
bool jointServoCalcs(const control_msgs::JointJog &cmd, trajectory_msgs::JointTrajectory &joint_trajectory)
Do servoing calculations for direct commands to a joint.
geometry_msgs::TwistStamped twist_stamped_cmd_
control_msgs::JointJog joint_servo_cmd_
ros::Subscriber twist_stamped_sub_
bool twist_command_is_stale_
std::array< bool, 6 > control_dimensions_
moveit_servo
Author(s): Brian O'Neil, Andy Zelenak
, Blake Anderson, Alexander Rössler , Tyler Weaver
autogenerated on Sat May 3 2025 02:27:56