Program Listing for File interaction.h

Return to documentation for file (include/moveit/robot_interaction/interaction.h)

/*********************************************************************
 * Software License Agreement (BSD License)
 *
 *  Copyright (c) 2014, SRI International
 *  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 Willow Garage 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 OWNER 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.
 *********************************************************************/

/* Author: Acorn Pooley */

#pragma once

#include <visualization_msgs/msg/interactive_marker_feedback.hpp>
#include <visualization_msgs/msg/interactive_marker.hpp>
#include <interactive_markers/menu_handler.hpp>
#include <moveit/robot_state/robot_state.h>
#include <functional>
#include <thread>

namespace moveit
{
namespace core
{
class RobotState;
}
}  // namespace moveit

namespace robot_interaction
{
namespace InteractionStyle
{
enum InteractionStyle
{
  POSITION_ARROWS = 1,      // arrows to change position
  ORIENTATION_CIRCLES = 2,  // circles to change orientation
  POSITION_SPHERE = 4,      // sphere: drag to change position
  ORIENTATION_SPHERE = 8,   // sphere: drag to change orientation
  POSITION_EEF = 16,        // drag end effector to change position
  ORIENTATION_EEF = 32,     // drag end effector to change orientation
  FIXED = 64,               // keep arrow and circle axis fixed

  POSITION = POSITION_ARROWS | POSITION_SPHERE | POSITION_EEF,
  ORIENTATION = ORIENTATION_CIRCLES | ORIENTATION_SPHERE | ORIENTATION_EEF,
  SIX_DOF = POSITION | ORIENTATION,
  SIX_DOF_SPHERE = POSITION_SPHERE | ORIENTATION_SPHERE,
  POSITION_NOSPHERE = POSITION_ARROWS | POSITION_EEF,
  ORIENTATION_NOSPHERE = ORIENTATION_CIRCLES | ORIENTATION_EEF,
  SIX_DOF_NOSPHERE = POSITION_NOSPHERE | ORIENTATION_NOSPHERE
};
}  // namespace InteractionStyle

typedef std::function<bool(const moveit::core::RobotState& state, visualization_msgs::msg::InteractiveMarker& marker)>
    InteractiveMarkerConstructorFn;

typedef std::function<bool(moveit::core::RobotState& state,
                           const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback)>
    ProcessFeedbackFn;

typedef std::function<bool(const moveit::core::RobotState&, geometry_msgs::msg::Pose&)> InteractiveMarkerUpdateFn;

struct GenericInteraction
{
  // Callback to construct interactive marker.
  // See comment on typedef above.
  InteractiveMarkerConstructorFn construct_marker;

  // Callback to handle interactive marker feedback messages.
  // See comment on typedef above.
  ProcessFeedbackFn process_feedback;

  // Callback to update marker pose when RobotState changes.
  // See comment on typedef above.
  InteractiveMarkerUpdateFn update_pose;

  // Suffix added to name of markers.
  // Automatically generated.
  std::string marker_name_suffix;
};

struct EndEffectorInteraction
{
  std::string parent_group;

  std::string parent_link;

  std::string eef_group;

  InteractionStyle::InteractionStyle interaction;

  double size;
};

struct JointInteraction
{
  std::string connecting_link;

  std::string parent_frame;

  std::string joint_name;

  unsigned int dof;

  double size;
};
}  // namespace robot_interaction