Program Listing for File common.hpp
↰ Return to documentation for file (include/moveit_servo/utils/common.hpp
)
/*******************************************************************************
* BSD 3-Clause License
*
* Copyright (c) 2019, Los Alamos National Security, LLC
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright notice, this
* list of conditions and the following disclaimer.
*
* * Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
*
* * Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*******************************************************************************/
/* Title : utils.hpp
* Project : moveit_servo
* Created : 05/17/2023
* Author : Andy Zelenak, V Mohammed Ibrahim
*
* Description : The utility functions used by MoveIt Servo.
*/
#pragma once
#include <moveit_servo_lib_parameters.hpp>
#include <moveit_servo/utils/datatypes.hpp>
#include <moveit/planning_scene_monitor/planning_scene_monitor.h>
#include <moveit/robot_model/joint_model_group.h>
#include <moveit/robot_state/robot_state.h>
#include <sensor_msgs/msg/joint_state.hpp>
#include <std_msgs/msg/float64_multi_array.hpp>
#include <tf2_eigen/tf2_eigen.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#include <trajectory_msgs/msg/joint_trajectory.hpp>
namespace moveit_servo
{
// A minimum of 3 points are used to help with interpolation when creating trajectory messages.
constexpr int MIN_POINTS_FOR_TRAJ_MSG = 3;
std::optional<std::string> getIKSolverBaseFrame(const moveit::core::RobotStatePtr& robot_state,
const std::string& group_name);
std::optional<std::string> getIKSolverTipFrame(const moveit::core::RobotStatePtr& robot_state,
const std::string& group_name);
bool isValidCommand(const Eigen::VectorXd& command);
bool isValidCommand(const Eigen::Isometry3d& command);
bool isValidCommand(const TwistCommand& command);
bool isValidCommand(const PoseCommand& command);
geometry_msgs::msg::Pose poseFromCartesianDelta(const Eigen::VectorXd& delta_x,
const Eigen::Isometry3d& base_to_tip_frame_transform);
std::optional<trajectory_msgs::msg::JointTrajectory>
composeTrajectoryMessage(const servo::Params& servo_params, const std::deque<KinematicState>& joint_cmd_rolling_window);
void updateSlidingWindow(KinematicState& next_joint_state, std::deque<KinematicState>& joint_cmd_rolling_window,
double max_expected_latency, const rclcpp::Time& cur_time);
std_msgs::msg::Float64MultiArray composeMultiArrayMessage(const servo::Params& servo_params,
const KinematicState& joint_state);
std::pair<double, StatusCode> velocityScalingFactorForSingularity(const moveit::core::RobotStatePtr& robot_state,
const Eigen::VectorXd& target_delta_x,
const servo::Params& servo_params);
double jointLimitVelocityScalingFactor(const Eigen::VectorXd& velocities,
const moveit::core::JointBoundsVector& joint_bounds, double scaling_override);
std::vector<size_t> jointVariablesToHalt(const Eigen::VectorXd& positions, const Eigen::VectorXd& velocities,
const moveit::core::JointBoundsVector& joint_bounds,
const std::vector<double>& margins);
geometry_msgs::msg::TransformStamped convertIsometryToTransform(const Eigen::Isometry3d& eigen_tf,
const std::string& parent_frame,
const std::string& child_frame);
PoseCommand poseFromPoseStamped(const geometry_msgs::msg::PoseStamped& msg);
planning_scene_monitor::PlanningSceneMonitorPtr createPlanningSceneMonitor(const rclcpp::Node::SharedPtr& node,
const servo::Params& servo_params);
KinematicState extractRobotState(const moveit::core::RobotStatePtr& robot_state, const std::string& move_group_name);
} // namespace moveit_servo