jog_calcs.h
Go to the documentation of this file.
1 /*******************************************************************************
2  * Title : jog_calcs.h
3  * Project : moveit_jog_arm
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 // System
42 #include <atomic>
43 
44 // ROS
47 #include <std_msgs/Int8.h>
48 
49 // moveit_jog_arm
50 #include "jog_arm_data.h"
51 #include "low_pass_filter.h"
52 #include "status_codes.h"
53 
54 namespace moveit_jog_arm
55 {
56 class JogCalcs
57 {
58 public:
59  JogCalcs(const JogArmParameters& parameters, const robot_model_loader::RobotModelLoaderPtr& model_loader_ptr);
60 
61  void startMainLoop(JogArmShared& shared_variables);
62 
66  bool isInitialized();
67 
68 protected:
70 
71  // Flag that robot state is up to date, end effector transform is known
72  std::atomic<bool> is_initialized_;
73 
75  bool cartesianJogCalcs(geometry_msgs::TwistStamped& cmd, JogArmShared& shared_variables);
76 
78  bool jointJogCalcs(const control_msgs::JointJog& cmd, JogArmShared& shared_variables);
79 
81  void updateCachedStatus(JogArmShared& shared_variables);
82 
84  bool updateJoints(JogArmShared& shared_variables);
85 
89  Eigen::VectorXd scaleCartesianCommand(const geometry_msgs::TwistStamped& command) const;
90 
94  Eigen::VectorXd scaleJointCommand(const control_msgs::JointJog& command) const;
95 
96  bool addJointIncrements(sensor_msgs::JointState& output, const Eigen::VectorXd& increments) const;
97 
101  void suddenHalt(trajectory_msgs::JointTrajectory& joint_traj);
102  void suddenHalt(Eigen::ArrayXd& delta_theta);
103 
105  void publishStatus() const;
106 
108  void enforceSRDFAccelVelLimits(Eigen::ArrayXd& delta_theta);
109 
111  bool enforceSRDFPositionLimits(trajectory_msgs::JointTrajectory& new_joint_traj);
112 
116  double velocityScalingFactorForSingularity(const Eigen::VectorXd& commanded_velocity,
117  const Eigen::JacobiSVD<Eigen::MatrixXd>& svd,
118  const Eigen::MatrixXd& jacobian, const Eigen::MatrixXd& pseudo_inverse);
119 
126  void applyVelocityScaling(JogArmShared& shared_variables, Eigen::ArrayXd& delta_theta, double singularity_scale);
127 
129  trajectory_msgs::JointTrajectory composeJointTrajMessage(sensor_msgs::JointState& joint_state) const;
130 
132  void lowPassFilterPositions(sensor_msgs::JointState& joint_state);
133 
135  void calculateJointVelocities(sensor_msgs::JointState& joint_state, const Eigen::ArrayXd& delta_theta);
136 
141 
145  void insertRedundantPointsIntoTrajectory(trajectory_msgs::JointTrajectory& trajectory, int count) const;
146 
154  void removeDimension(Eigen::MatrixXd& matrix, Eigen::VectorXd& delta_x, unsigned int row_to_remove);
155 
157 
158  moveit::core::RobotStatePtr kinematic_state_;
159 
160  // incoming_joint_state_ is the incoming message. It may contain passive joints or other joints we don't care about.
161  // internal_joint_state_ is used in jog calculations. It shouldn't be relied on to be accurate.
162  // original_joint_state_ is the same as incoming_joint_state_ except it only contains the joints jog_arm acts on.
164  std::map<std::string, std::size_t> joint_state_name_map_;
165  trajectory_msgs::JointTrajectory outgoing_command_;
166 
167  std::vector<LowPassFilter> position_filters_;
168 
170 
172 
174 
175  // Use ArrayXd type to enable more coefficient-wise operations
176  Eigen::ArrayXd delta_theta_;
177  Eigen::ArrayXd prev_joint_velocity_;
178 
179  Eigen::Isometry3d tf_moveit_to_cmd_frame_;
180 
182 
184 
186 };
187 } // namespace moveit_jog_arm
void enforceSRDFAccelVelLimits(Eigen::ArrayXd &delta_theta)
Scale the delta theta to match joint velocity/acceleration limits.
Definition: jog_calcs.cpp:565
Eigen::ArrayXd prev_joint_velocity_
Definition: jog_calcs.h:177
ros::Publisher status_pub_
Definition: jog_calcs.h:169
moveit::core::RobotStatePtr kinematic_state_
Definition: jog_calcs.h:158
void lowPassFilterPositions(sensor_msgs::JointState &joint_state)
Smooth position commands with a lowpass filter.
Definition: jog_calcs.cpp:433
std::vector< LowPassFilter > position_filters_
Definition: jog_calcs.h:167
trajectory_msgs::JointTrajectory composeJointTrajMessage(sensor_msgs::JointState &joint_state) const
Compose the outgoing JointTrajectory message.
Definition: jog_calcs.cpp:449
double velocityScalingFactorForSingularity(const Eigen::VectorXd &commanded_velocity, const Eigen::JacobiSVD< Eigen::MatrixXd > &svd, const Eigen::MatrixXd &jacobian, const Eigen::MatrixXd &pseudo_inverse)
Possibly calculate a velocity scaling factor, due to proximity of singularity and direction of motion...
Definition: jog_calcs.cpp:498
void insertRedundantPointsIntoTrajectory(trajectory_msgs::JointTrajectory &trajectory, int count) const
Gazebo simulations have very strict message timestamp requirements. Satisfy Gazebo by stuffing multip...
Definition: jog_calcs.cpp:422
void updateCachedStatus(JogArmShared &shared_variables)
Update the stashed status so it can be retrieved asynchronously.
Definition: jog_calcs.cpp:385
bool addJointIncrements(sensor_msgs::JointState &output, const Eigen::VectorXd &increments) const
Definition: jog_calcs.cpp:815
JogCalcs(const JogArmParameters &parameters, const robot_model_loader::RobotModelLoaderPtr &model_loader_ptr)
Definition: jog_calcs.cpp:47
ros::NodeHandle nh_
Definition: jog_calcs.h:69
bool enforceSRDFPositionLimits(trajectory_msgs::JointTrajectory &new_joint_traj)
Avoid overshooting joint limits.
Definition: jog_calcs.cpp:639
bool jointJogCalcs(const control_msgs::JointJog &cmd, JogArmShared &shared_variables)
Do jogging calculations for direct commands to a joint.
Definition: jog_calcs.cpp:357
bool convertDeltasToOutgoingCmd()
Convert joint deltas to an outgoing JointTrajectory command. This happens for joint commands and Cart...
Definition: jog_calcs.cpp:391
ros::Rate default_sleep_rate_
Definition: jog_calcs.h:185
bool isInitialized()
Check if the robot state is being updated and the end effector transform is known.
Definition: jog_calcs.cpp:247
bool cartesianJogCalcs(geometry_msgs::TwistStamped &cmd, JogArmShared &shared_variables)
Do jogging calculations for Cartesian twist commands.
Definition: jog_calcs.cpp:253
void applyVelocityScaling(JogArmShared &shared_variables, Eigen::ArrayXd &delta_theta, double singularity_scale)
Definition: jog_calcs.cpp:477
JogArmParameters parameters_
Definition: jog_calcs.h:173
sensor_msgs::JointState incoming_joint_state_
Definition: jog_calcs.h:163
Eigen::VectorXd scaleJointCommand(const control_msgs::JointJog &command) const
If incoming velocity commands are from a unitless joystick, scale them to physical units...
Definition: jog_calcs.cpp:780
std::map< std::string, std::size_t > joint_state_name_map_
Definition: jog_calcs.h:164
sensor_msgs::JointState internal_joint_state_
Definition: jog_calcs.h:163
void calculateJointVelocities(sensor_msgs::JointState &joint_state, const Eigen::ArrayXd &delta_theta)
Convert an incremental position command to joint velocity message.
Definition: jog_calcs.cpp:441
void publishStatus() const
Publish the status of the jogger to a ROS topic.
Definition: jog_calcs.cpp:678
std::atomic< bool > is_initialized_
Definition: jog_calcs.h:72
void suddenHalt(trajectory_msgs::JointTrajectory &joint_traj)
Suddenly halt for a joint limit or other critical issue. Is handled differently for position vs...
Definition: jog_calcs.cpp:694
const int gazebo_redundant_message_count_
Definition: jog_calcs.h:181
bool updateJoints(JogArmShared &shared_variables)
Parse the incoming joint msg for the joints of our MoveGroup.
Definition: jog_calcs.cpp:716
const moveit::core::JointModelGroup * joint_model_group_
Definition: jog_calcs.h:156
Eigen::VectorXd scaleCartesianCommand(const geometry_msgs::TwistStamped &command) const
If incoming velocity commands are from a unitless joystick, scale them to physical units...
Definition: jog_calcs.cpp:750
sensor_msgs::JointState original_joint_state_
Definition: jog_calcs.h:163
Eigen::Isometry3d tf_moveit_to_cmd_frame_
Definition: jog_calcs.h:179
void removeDimension(Eigen::MatrixXd &matrix, Eigen::VectorXd &delta_x, unsigned int row_to_remove)
Definition: jog_calcs.cpp:834
Eigen::ArrayXd delta_theta_
Definition: jog_calcs.h:176
void startMainLoop(JogArmShared &shared_variables)
Definition: jog_calcs.cpp:67
trajectory_msgs::JointTrajectory outgoing_command_
Definition: jog_calcs.h:165


moveit_jog_arm
Author(s): Brian O'Neil, Andy Zelenak , Blake Anderson, Alexander Rössler
autogenerated on Fri Jun 5 2020 03:53:46