servo_calcs.h
Go to the documentation of this file.
1 /*******************************************************************************
2  * Title : servo_calcs.h
3  * Project : moveit_servo
4  * Created : 1/11/2019
5  * Author : Brian O'Neil, Andy Zelenak, Blake Anderson
6  *
7  * BSD 3-Clause License
8  *
9  * Copyright (c) 2019, Los Alamos National Security, LLC
10  * All rights reserved.
11  *
12  * Redistribution and use in source and binary forms, with or without
13  * modification, are permitted provided that the following conditions are met:
14  *
15  * * Redistributions of source code must retain the above copyright notice, this
16  * list of conditions and the following disclaimer.
17  *
18  * * Redistributions in binary form must reproduce the above copyright notice,
19  * this list of conditions and the following disclaimer in the documentation
20  * and/or other materials provided with the distribution.
21  *
22  * * Neither the name of the copyright holder nor the names of its
23  * contributors may be used to endorse or promote products derived from
24  * this software without specific prior written permission.
25  *
26  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
27  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
28  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
29  * ARE
30  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
31  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
32  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
33  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
34  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
35  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
36  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
37  *******************************************************************************/
38 
39 #pragma once
40 
41 // C++
42 #include <condition_variable>
43 #include <mutex>
44 #include <thread>
45 #include <atomic>
46 
47 // ROS
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>
59 #include <tf2_eigen/tf2_eigen.h>
60 #include <trajectory_msgs/JointTrajectory.h>
61 
62 // moveit_servo
66 
67 namespace moveit_servo
68 {
69 class ServoCalcs
70 {
71 public:
72  ServoCalcs(ros::NodeHandle& nh, ServoParameters& parameters,
73  const planning_scene_monitor::PlanningSceneMonitorPtr& planning_scene_monitor);
74 
75  ~ServoCalcs();
76 
78  void start();
79 
87  bool getCommandFrameTransform(Eigen::Isometry3d& transform);
88  bool getCommandFrameTransform(geometry_msgs::TransformStamped& transform);
89 
97  bool getEEFrameTransform(Eigen::Isometry3d& transform);
98  bool getEEFrameTransform(geometry_msgs::TransformStamped& transform);
99 
101  void setPaused(bool paused);
102 
106  void changeRobotLinkCommandFrame(const std::string& new_command_frame);
107 
108  // Give test access to private/protected methods
109  friend class ServoFixture;
110 
111 private:
113  void mainCalcLoop();
114 
117 
119  void stop();
120 
122  bool cartesianServoCalcs(geometry_msgs::TwistStamped& cmd, trajectory_msgs::JointTrajectory& joint_trajectory);
123 
125  bool jointServoCalcs(const control_msgs::JointJog& cmd, trajectory_msgs::JointTrajectory& joint_trajectory);
126 
128  void updateJoints();
129 
133  Eigen::VectorXd scaleCartesianCommand(const geometry_msgs::TwistStamped& command) const;
134 
138  Eigen::VectorXd scaleJointCommand(const control_msgs::JointJog& command) const;
139 
140  bool addJointIncrements(sensor_msgs::JointState& output, const Eigen::VectorXd& increments) const;
141 
145  void suddenHalt(trajectory_msgs::JointTrajectory& joint_trajectory);
146 
148  void enforceVelLimits(Eigen::ArrayXd& delta_theta);
149 
151  bool enforcePositionLimits(sensor_msgs::JointState& joint_state);
152 
156  double velocityScalingFactorForSingularity(const Eigen::VectorXd& commanded_velocity,
157  const Eigen::JacobiSVD<Eigen::MatrixXd>& svd,
158  const Eigen::MatrixXd& pseudo_inverse);
159 
165  void applyVelocityScaling(Eigen::ArrayXd& delta_theta, double singularity_scale);
166 
168  void composeJointTrajMessage(const sensor_msgs::JointState& joint_state,
169  trajectory_msgs::JointTrajectory& joint_trajectory) const;
170 
172  void lowPassFilterPositions(sensor_msgs::JointState& joint_state);
173 
175  void resetLowPassFilters(const sensor_msgs::JointState& joint_state);
176 
178  void calculateJointVelocities(sensor_msgs::JointState& joint_state, const Eigen::ArrayXd& delta_theta);
179 
183  bool convertDeltasToOutgoingCmd(trajectory_msgs::JointTrajectory& joint_trajectory);
184 
188  void insertRedundantPointsIntoTrajectory(trajectory_msgs::JointTrajectory& joint_trajectory, int count) const;
189 
197  void removeDimension(Eigen::MatrixXd& matrix, Eigen::VectorXd& delta_x, unsigned int row_to_remove);
198 
199  /* \brief Callback for joint subsription */
200  void jointStateCB(const sensor_msgs::JointStateConstPtr& msg);
201 
202  /* \brief Command callbacks */
203  void twistStampedCB(const geometry_msgs::TwistStampedConstPtr& msg);
204  void jointCmdCB(const control_msgs::JointJogConstPtr& msg);
205  void collisionVelocityScaleCB(const std_msgs::Float64ConstPtr& msg);
206 
215  bool changeDriftDimensions(moveit_msgs::ChangeDriftDimensions::Request& req,
216  moveit_msgs::ChangeDriftDimensions::Response& res);
217 
219  bool changeControlDimensions(moveit_msgs::ChangeControlDimensions::Request& req,
220  moveit_msgs::ChangeControlDimensions::Response& res);
221 
223  bool resetServoStatus(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res);
224 
226 
227  // Parameters from yaml
228  ServoParameters& parameters_;
229 
230  // Pointer to the collision environment
231  planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
232 
233  // Track the number of cycles during which motion has not occurred.
234  // Will avoid re-publishing zero velocities endlessly.
235  int zero_velocity_count_ = 0;
236 
237  // Flag for staying inactive while there are no incoming commands
238  bool wait_for_servo_commands_ = true;
239 
240  // Flag saying if the filters were updated during the timer callback
241  bool updated_filters_ = false;
242 
243  // Nonzero status flags
244  bool have_nonzero_twist_stamped_ = false;
245  bool have_nonzero_joint_command_ = false;
246  bool have_nonzero_command_ = false;
247 
248  // Incoming command messages
249  geometry_msgs::TwistStamped twist_stamped_cmd_;
250  control_msgs::JointJog joint_servo_cmd_;
251 
253 
254  moveit::core::RobotStatePtr current_state_;
255 
256  // incoming_joint_state_ is the incoming message. It may contain passive joints or other joints we don't care about.
257  // (mutex protected below)
258  // internal_joint_state_ is used in servo calculations. It shouldn't be relied on to be accurate.
259  // original_joint_state_ is the same as incoming_joint_state_ except it only contains the joints the servo node acts
260  // on.
261  sensor_msgs::JointState internal_joint_state_, original_joint_state_;
262  std::map<std::string, std::size_t> joint_state_name_map_;
263 
264  std::vector<LowPassFilter> position_filters_;
265 
266  trajectory_msgs::JointTrajectoryConstPtr last_sent_command_;
267 
268  // ROS
279 
280  // Main tracking / result publisher loop
281  std::thread thread_;
282  bool stop_requested_;
283 
284  // Status
286  std::atomic<bool> paused_;
287  bool twist_command_is_stale_ = false;
288  bool joint_command_is_stale_ = false;
289  bool ok_to_publish_ = false;
290  double collision_velocity_scale_ = 1.0;
291 
292  // Use ArrayXd type to enable more coefficient-wise operations
293  Eigen::ArrayXd delta_theta_;
294  Eigen::ArrayXd prev_joint_velocity_;
295 
296  const int gazebo_redundant_message_count_ = 30;
297 
298  uint num_joints_;
299 
300  // True -> allow drift in this dimension. In the command frame. [x, y, z, roll, pitch, yaw]
301  std::array<bool, 6> drift_dimensions_ = { { false, false, false, false, false, false } };
302 
303  // The dimesions to control. In the command frame. [x, y, z, roll, pitch, yaw]
304  std::array<bool, 6> control_dimensions_ = { { true, true, true, true, true, true } };
305 
306  // input_mutex_ is used to protect the state below it
307  mutable std::mutex input_mutex_;
308  Eigen::Isometry3d tf_moveit_to_robot_cmd_frame_;
309  Eigen::Isometry3d tf_moveit_to_ee_frame_;
310  geometry_msgs::TwistStampedConstPtr latest_twist_stamped_;
311  control_msgs::JointJogConstPtr latest_joint_cmd_;
314  bool latest_nonzero_twist_stamped_ = false;
315  bool latest_nonzero_joint_cmd_ = false;
316 
317  // input condition variable used for low latency mode
318  std::condition_variable input_cv_;
319  bool new_input_cmd_ = false;
320 };
321 } // namespace moveit_servo
moveit_servo::ServoCalcs::stop_requested_
bool stop_requested_
Definition: servo_calcs.h:354
moveit_servo::ServoCalcs::collision_velocity_scale_sub_
ros::Subscriber collision_velocity_scale_sub_
Definition: servo_calcs.h:344
planning_scene_monitor
moveit_servo::ServoCalcs::changeRobotLinkCommandFrame
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...
Definition: servo_calcs.cpp:1137
moveit_servo::ServoCalcs::latest_joint_cmd_
control_msgs::JointJogConstPtr latest_joint_cmd_
Definition: servo_calcs.h:383
moveit_servo::ServoCalcs::jointCmdCB
void jointCmdCB(const control_msgs::JointJogConstPtr &msg)
Definition: servo_calcs.cpp:1079
moveit_servo::ServoCalcs::ok_to_publish_
bool ok_to_publish_
Definition: servo_calcs.h:361
moveit_servo::ServoCalcs::internal_joint_state_
sensor_msgs::JointState internal_joint_state_
Definition: servo_calcs.h:333
ros::Publisher
moveit_servo::ServoCalcs::joint_state_name_map_
std::map< std::string, std::size_t > joint_state_name_map_
Definition: servo_calcs.h:334
moveit_servo::ServoCalcs::collisionVelocityScaleCB
void collisionVelocityScaleCB(const std_msgs::Float64ConstPtr &msg)
Definition: servo_calcs.cpp:1093
moveit_servo::ServoCalcs::wait_for_servo_commands_
bool wait_for_servo_commands_
Definition: servo_calcs.h:310
moveit_servo::ServoCalcs::stop
void stop()
Stop the currently running thread.
Definition: servo_calcs.cpp:207
moveit_servo::ServoCalcs::addJointIncrements
bool addJointIncrements(sensor_msgs::JointState &output, const Eigen::VectorXd &increments) const
Definition: servo_calcs.cpp:984
tf2_eigen.h
moveit_servo::ServoCalcs::joint_cmd_sub_
ros::Subscriber joint_cmd_sub_
Definition: servo_calcs.h:343
moveit_servo::ServoCalcs::calculateJointVelocities
void calculateJointVelocities(sensor_msgs::JointState &joint_state, const Eigen::ArrayXd &delta_theta)
Convert an incremental position command to joint velocity message.
Definition: servo_calcs.cpp:635
moveit_servo::ServoCalcs::status_pub_
ros::Publisher status_pub_
Definition: servo_calcs.h:345
moveit_servo::ServoCalcs::control_dimensions_server_
ros::ServiceServer control_dimensions_server_
Definition: servo_calcs.h:349
moveit_servo::ServoCalcs::tf_moveit_to_ee_frame_
Eigen::Isometry3d tf_moveit_to_ee_frame_
Definition: servo_calcs.h:381
moveit_servo::ServoCalcs::twistStampedCB
void twistStampedCB(const geometry_msgs::TwistStampedConstPtr &msg)
Definition: servo_calcs.cpp:1065
moveit_servo::ServoCalcs::updated_filters_
bool updated_filters_
Definition: servo_calcs.h:313
moveit_servo::ServoCalcs::cartesianServoCalcs
bool cartesianServoCalcs(geometry_msgs::TwistStamped &cmd, trajectory_msgs::JointTrajectory &joint_trajectory)
Do servoing calculations for Cartesian twist commands.
Definition: servo_calcs.cpp:434
moveit_servo::ServoCalcs::drift_dimensions_
std::array< bool, 6 > drift_dimensions_
Definition: servo_calcs.h:373
moveit_servo::ServoCalcs::have_nonzero_command_
bool have_nonzero_command_
Definition: servo_calcs.h:318
moveit_servo::ServoCalcs::ServoCalcs
ServoCalcs(ros::NodeHandle &nh, ServoParameters &parameters, const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor)
Definition: servo_calcs.cpp:87
moveit_servo::ServoCalcs::zero_velocity_count_
int zero_velocity_count_
Definition: servo_calcs.h:307
moveit_servo::ServoCalcs::planning_scene_monitor_
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
Definition: servo_calcs.h:303
robot_model_loader.h
moveit_servo::ServoCalcs::new_input_cmd_
bool new_input_cmd_
Definition: servo_calcs.h:391
moveit_servo::ServoCalcs::suddenHalt
void suddenHalt(trajectory_msgs::JointTrajectory &joint_trajectory)
Suddenly halt for a joint limit or other critical issue. Is handled differently for position vs....
Definition: servo_calcs.cpp:829
moveit_servo::ServoCalcs::composeJointTrajMessage
void composeJointTrajMessage(const sensor_msgs::JointState &joint_state, trajectory_msgs::JointTrajectory &joint_trajectory) const
Compose the outgoing JointTrajectory message.
Definition: servo_calcs.cpp:643
moveit_servo::ServoCalcs::ServoFixture
friend class ServoFixture
Definition: servo_calcs.h:181
moveit_servo::ServoCalcs::collision_velocity_scale_
double collision_velocity_scale_
Definition: servo_calcs.h:362
moveit_servo::ServoCalcs::input_mutex_
std::mutex input_mutex_
Definition: servo_calcs.h:379
moveit_servo::ServoCalcs::num_joints_
uint num_joints_
Definition: servo_calcs.h:370
moveit_servo::ServoCalcs::getCommandFrameTransform
bool getCommandFrameTransform(Eigen::Isometry3d &transform)
Definition: servo_calcs.cpp:1020
moveit_servo::ServoCalcs::removeDimension
void removeDimension(Eigen::MatrixXd &matrix, Eigen::VectorXd &delta_x, unsigned int row_to_remove)
Definition: servo_calcs.cpp:1004
ros::ServiceServer
moveit_servo::ServoCalcs::latest_joint_command_stamp_
ros::Time latest_joint_command_stamp_
Definition: servo_calcs.h:385
status_codes.h
moveit_servo::ServoCalcs::nh_
ros::NodeHandle nh_
Definition: servo_calcs.h:297
moveit_servo::ServoCalcs::original_joint_state_
sensor_msgs::JointState original_joint_state_
Definition: servo_calcs.h:333
moveit_servo::ServoCalcs::convertDeltasToOutgoingCmd
bool convertDeltasToOutgoingCmd(trajectory_msgs::JointTrajectory &joint_trajectory)
Convert joint deltas to an outgoing JointTrajectory command. This happens for joint commands and Cart...
Definition: servo_calcs.cpp:572
moveit_servo::ServoCalcs::position_filters_
std::vector< LowPassFilter > position_filters_
Definition: servo_calcs.h:336
planning_scene_monitor.h
moveit_servo::ServoCalcs::current_state_
moveit::core::RobotStatePtr current_state_
Definition: servo_calcs.h:326
moveit_servo::ServoCalcs::worst_case_stop_time_pub_
ros::Publisher worst_case_stop_time_pub_
Definition: servo_calcs.h:346
moveit_servo::ServoCalcs::jointStateCB
void jointStateCB(const sensor_msgs::JointStateConstPtr &msg)
moveit_servo::ServoCalcs::latest_nonzero_twist_stamped_
bool latest_nonzero_twist_stamped_
Definition: servo_calcs.h:386
moveit_servo
Definition: collision_check.h:50
moveit_servo::ServoCalcs::updateJoints
void updateJoints()
Parse the incoming joint msg for the joints of our MoveGroup.
Definition: servo_calcs.cpp:864
moveit_servo::ServoCalcs::lowPassFilterPositions
void lowPassFilterPositions(sensor_msgs::JointState &joint_state)
Smooth position commands with a lowpass filter.
Definition: servo_calcs.cpp:615
moveit_servo::ServoCalcs::delta_theta_
Eigen::ArrayXd delta_theta_
Definition: servo_calcs.h:365
moveit_servo::StatusCode
StatusCode
Definition: status_codes.h:82
moveit_servo::ServoCalcs::joint_command_is_stale_
bool joint_command_is_stale_
Definition: servo_calcs.h:360
moveit_servo::ServoCalcs::latest_twist_stamped_
geometry_msgs::TwistStampedConstPtr latest_twist_stamped_
Definition: servo_calcs.h:382
moveit_servo::ServoCalcs::parameters_
ServoParameters & parameters_
Definition: servo_calcs.h:300
moveit_servo::ServoCalcs::changeDriftDimensions
bool changeDriftDimensions(moveit_msgs::ChangeDriftDimensions::Request &req, moveit_msgs::ChangeDriftDimensions::Response &res)
Definition: servo_calcs.cpp:1098
moveit_servo::ServoCalcs::~ServoCalcs
~ServoCalcs()
Definition: servo_calcs.cpp:157
moveit_servo::ServoCalcs::paused_
std::atomic< bool > paused_
Definition: servo_calcs.h:358
moveit_servo::ServoCalcs::changeControlDimensions
bool changeControlDimensions(moveit_msgs::ChangeControlDimensions::Request &req, moveit_msgs::ChangeControlDimensions::Response &res)
Service callback for changing servoing dimensions (e.g. ignore rotation about X)
Definition: servo_calcs.cpp:1112
moveit_servo::ServoCalcs::gazebo_redundant_message_count_
const int gazebo_redundant_message_count_
Definition: servo_calcs.h:368
moveit_servo::ServoCalcs::getEEFrameTransform
bool getEEFrameTransform(Eigen::Isometry3d &transform)
Definition: servo_calcs.cpp:1043
moveit_servo::ServoCalcs::reset_servo_status_
ros::ServiceServer reset_servo_status_
Definition: servo_calcs.h:350
moveit_servo::ServoCalcs::setPaused
void setPaused(bool paused)
Pause or unpause processing servo commands while keeping the timers alive.
Definition: servo_calcs.cpp:1132
moveit_servo::ServoCalcs::drift_dimensions_server_
ros::ServiceServer drift_dimensions_server_
Definition: servo_calcs.h:348
moveit_servo::ServoCalcs::resetLowPassFilters
void resetLowPassFilters(const sensor_msgs::JointState &joint_state)
Set the filters to the specified values.
Definition: servo_calcs.cpp:625
moveit_servo::ServoCalcs::resetServoStatus
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.
Definition: servo_calcs.cpp:1126
moveit_servo::ServoCalcs::enforceVelLimits
void enforceVelLimits(Eigen::ArrayXd &delta_theta)
Scale the delta theta to match joint velocity/acceleration limits.
Definition: servo_calcs.cpp:759
moveit_servo::ServoCalcs::have_nonzero_joint_command_
bool have_nonzero_joint_command_
Definition: servo_calcs.h:317
moveit_servo::ServoCalcs::joint_model_group_
const moveit::core::JointModelGroup * joint_model_group_
Definition: servo_calcs.h:324
moveit_servo::ServoCalcs::insertRedundantPointsIntoTrajectory
void insertRedundantPointsIntoTrajectory(trajectory_msgs::JointTrajectory &joint_trajectory, int count) const
Gazebo simulations have very strict message timestamp requirements. Satisfy Gazebo by stuffing multip...
Definition: servo_calcs.cpp:602
moveit_servo::ServoCalcs::velocityScalingFactorForSingularity
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...
Definition: servo_calcs.cpp:694
moveit_servo::ServoCalcs::enforcePositionLimits
bool enforcePositionLimits(sensor_msgs::JointState &joint_state)
Avoid overshooting joint limits.
Definition: servo_calcs.cpp:783
ros::Time
moveit_servo::ServoCalcs::have_nonzero_twist_stamped_
bool have_nonzero_twist_stamped_
Definition: servo_calcs.h:316
moveit_servo::ServoCalcs::input_cv_
std::condition_variable input_cv_
Definition: servo_calcs.h:390
moveit_servo::ServoCalcs::joint_state_sub_
ros::Subscriber joint_state_sub_
Definition: servo_calcs.h:341
moveit_servo::ServoCalcs::thread_
std::thread thread_
Definition: servo_calcs.h:353
moveit_servo::ServoCalcs::outgoing_cmd_pub_
ros::Publisher outgoing_cmd_pub_
Definition: servo_calcs.h:347
moveit::core::JointModelGroup
moveit_servo::ServoCalcs::last_sent_command_
trajectory_msgs::JointTrajectoryConstPtr last_sent_command_
Definition: servo_calcs.h:338
moveit_servo::ServoCalcs::applyVelocityScaling
void applyVelocityScaling(Eigen::ArrayXd &delta_theta, double singularity_scale)
Definition: servo_calcs.cpp:670
moveit_servo::ServoCalcs::latest_twist_command_stamp_
ros::Time latest_twist_command_stamp_
Definition: servo_calcs.h:384
moveit_servo::ServoCalcs::scaleJointCommand
Eigen::VectorXd scaleJointCommand(const control_msgs::JointJog &command) const
If incoming velocity commands are from a unitless joystick, scale them to physical units....
Definition: servo_calcs.cpp:953
moveit_servo::ServoCalcs::start
void start()
Start the timer where we do work and publish outputs.
Definition: servo_calcs.cpp:162
moveit_servo::ServoCalcs::prev_joint_velocity_
Eigen::ArrayXd prev_joint_velocity_
Definition: servo_calcs.h:366
moveit_servo::ServoCalcs::scaleCartesianCommand
Eigen::VectorXd scaleCartesianCommand(const geometry_msgs::TwistStamped &command) const
If incoming velocity commands are from a unitless joystick, scale them to physical units....
Definition: servo_calcs.cpp:923
moveit_servo::ServoCalcs::mainCalcLoop
void mainCalcLoop()
Run the main calculation loop.
Definition: servo_calcs.cpp:228
servo_parameters.h
moveit_servo::ServoCalcs::calculateSingleIteration
void calculateSingleIteration()
Do calculations for a single iteration. Publish one outgoing command.
Definition: servo_calcs.cpp:268
moveit_servo::ServoCalcs::latest_nonzero_joint_cmd_
bool latest_nonzero_joint_cmd_
Definition: servo_calcs.h:387
moveit_servo::ServoCalcs::tf_moveit_to_robot_cmd_frame_
Eigen::Isometry3d tf_moveit_to_robot_cmd_frame_
Definition: servo_calcs.h:380
moveit_servo::ServoCalcs::jointServoCalcs
bool jointServoCalcs(const control_msgs::JointJog &cmd, trajectory_msgs::JointTrajectory &joint_trajectory)
Do servoing calculations for direct commands to a joint.
Definition: servo_calcs.cpp:546
moveit_servo::ServoCalcs::twist_stamped_cmd_
geometry_msgs::TwistStamped twist_stamped_cmd_
Definition: servo_calcs.h:321
moveit_servo::ServoCalcs::joint_servo_cmd_
control_msgs::JointJog joint_servo_cmd_
Definition: servo_calcs.h:322
moveit_servo::ServoCalcs::twist_stamped_sub_
ros::Subscriber twist_stamped_sub_
Definition: servo_calcs.h:342
moveit_servo::ServoCalcs::twist_command_is_stale_
bool twist_command_is_stale_
Definition: servo_calcs.h:359
moveit_servo::StatusCode::NO_WARNING
@ NO_WARNING
ros::NodeHandle
ros::Subscriber
moveit_servo::ServoCalcs::status_
StatusCode status_
Definition: servo_calcs.h:357
moveit_servo::ServoCalcs::control_dimensions_
std::array< bool, 6 > control_dimensions_
Definition: servo_calcs.h:376
low_pass_filter.h


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