Program Listing for File servo.hpp

Return to documentation for file (include/moveit_servo/servo.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       : servo.hpp
 *      Project     : moveit_servo
 *      Created     : 05/17/2023
 *      Author      : Brian O'Neil, Andy Zelenak, Blake Anderson, V Mohammed Ibrahim
 *
 *      Description : The core servoing logic.
 */

#pragma once

#include <moveit_servo_lib_parameters.hpp>
#include <moveit_servo/collision_monitor.hpp>
#include <moveit_servo/utils/command.hpp>
#include <moveit_servo/utils/datatypes.hpp>
#include <moveit/kinematics_base/kinematics_base.h>
#include <moveit/online_signal_smoothing/smoothing_base_class.h>
#include <moveit/planning_scene_monitor/planning_scene_monitor.h>
#include <pluginlib/class_loader.hpp>
#include <sensor_msgs/msg/joint_state.hpp>
#include <tf2_eigen/tf2_eigen.hpp>
#include <tf2_ros/transform_listener.h>
#include <variant>
#include <rclcpp/logger.hpp>
#include <queue>

namespace moveit_servo
{

class Servo
{
public:
  Servo(const rclcpp::Node::SharedPtr& node, std::shared_ptr<const servo::ParamListener> servo_param_listener,
        const planning_scene_monitor::PlanningSceneMonitorPtr& planning_scene_monitor);

  ~Servo();

  // Disable copy construction.
  Servo(const Servo&) = delete;

  // Disable copy assignment.
  Servo& operator=(Servo&) = delete;

  KinematicState getNextJointState(const moveit::core::RobotStatePtr& robot_state, const ServoInput& command);

  void setCommandType(const CommandType& command_type);

  CommandType getCommandType() const;

  StatusCode getStatus() const;

  std::string getStatusMessage() const;

  void setCollisionChecking(const bool check_collision);

  servo::Params& getParams();

  KinematicState getCurrentRobotState() const;

  std::pair<bool, KinematicState> smoothHalt(const KinematicState& halt_state);

  void doSmoothing(KinematicState& state);

  void resetSmoothing(const KinematicState& state);

private:
  std::optional<Eigen::Isometry3d> getPlanningToCommandFrameTransform(const std::string& command_frame,
                                                                      const std::string& planning_frame) const;

  std::optional<TwistCommand> toPlanningFrame(const TwistCommand& command, const std::string& planning_frame) const;

  std::optional<PoseCommand> toPlanningFrame(const PoseCommand& command, const std::string& planning_frame) const;

  Eigen::VectorXd jointDeltaFromCommand(const ServoInput& command, const moveit::core::RobotStatePtr& robot_state);

  bool validateParams(const servo::Params& servo_params) const;

  bool updateParams();

  void setSmoothingPlugin();

  KinematicState haltJoints(const std::vector<int>& joints_to_halt, const KinematicState& current_state,
                            const KinematicState& target_state) const;

  // Variables

  StatusCode servo_status_;
  // This needs to be threadsafe so it can be updated in realtime.
  std::atomic<CommandType> expected_command_type_;

  servo::Params servo_params_;
  const rclcpp::Node::SharedPtr node_;
  rclcpp::Logger logger_;
  std::shared_ptr<const servo::ParamListener> servo_param_listener_;
  planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;

  // This value will be updated by CollisionMonitor in a separate thread.
  std::atomic<double> collision_velocity_scale_ = 1.0;
  std::unique_ptr<CollisionMonitor> collision_monitor_;

  // Pointer to the (optional) smoothing plugin.
  pluginlib::UniquePtr<online_signal_smoothing::SmoothingBaseClass> smoother_ = nullptr;

  // Map between joint subgroup names and corresponding joint name - move group indices map
  std::unordered_map<std::string, JointNameToMoveGroupIndexMap> joint_name_to_index_maps_;
};

}  // namespace moveit_servo