From a4a49df29f974660538232bd4da7925e9d65ad35 Mon Sep 17 00:00:00 2001 From: Alexandre Vannobel <41082816+alexvannobel@users.noreply.github.com> Date: Wed, 5 Aug 2020 07:56:21 -0400 Subject: [PATCH] Simulation velocity control, documentation and examples update (#109) * Created interface class and put the RPC handlers in robot folder * Now the robot functions interface work just like before * Added templates and generation for simulated services * Added the simulation services to the driver headers * Added newly generated files to repo * Added simulation option to the driver so the gazebo package can launch the kortex_driver too, in a different mode * Adapt joint_limits files to correctly take prefix option * Change description and control files to support prefix option * Change MoveIt config launch and config files to enable prefix option - only SRDF modifications remain * Added xacro usage in SRDF files to be able to prefix joint names * Adjust ompl planning launch and config files to support prefixing joint names * Remove --inorder from xacro calls since it's default now * Set default gripper in launch files * Add namespace to launch file parameters passed to driver * Added class and implementation for simulator * Add stubs and register handlers for Action API * Add implementation for default actions and ReacAction/ReadAllActions * Added some unit tests for simulator and CreateAction implentation * Added the case where the prefix could be empty in XACRO * Added prefix support for fake controllers in MoveIt configs * Added a missing prefix value for Gen3 and fix the if and unless tags * Add test launch file to launch simulator unit tests * Don't create the gripper Move Group if no gripper on the arm * Added DeleteAction implementation and tests * Add implementation and tests for UpdateAction * Added basic frame for a threaded action executor * Added publishing for action topic before and after action execution * Added StopAction logic and tests for executing and aborting actions * Added stubs for other RPCs we want to support at first in simulation * Added implementation for other RPCs worth simulating * Added some data structure checks and TODOs in executors * Added tests for newly added RPCs * Remove merge artefacts * Added implementation for ReachJointAngles action - optimal duration implementation remain * Added KDL parsing and solvers construction * Add max velocities and max accelerations to joint_limits.yaml files * Add a helper to fill KortexError and finish velocity profiles implementation for ReachJointAngles * Now use the velocity profile data to fill the trajectory * Add implementation for angular position control * Add same ROS parameters than real arm and adjust first timestamp to not be 0 * Fix MoveIt config Gen3 lite home position * Added ReachPose implementation, twist limits still hardcoded * Add twist limits files for simulation * Use the correct Cartesian velocity and acceleration values for each arm and correctly use velocity limits in constraints * Add simulated feedback support and change current state to fetch joint_states instead of controller state * Added implementation for gripper control * Fixed a Robotiq 2F-140 typo in the moveit config * Added indexes for first arm joint and gripper joint because sometimes gripper joint is at the start of joint_states and sometimes it's at the end * Changed the way the individual position controllers are loaded and started as well as added service client in simulator to switch controllers based on RPC called * Added implementation for angular velocity control and added joint limits to simulation class. Will need a way to wrap-around angles now that velocity control for infinite spinning joint is on. * Added wrapping around in reach joint angles * Fix a problem with timestamps * Added an implementation for SendTwistCommand but not stable enough to be activated so handler is commented out * Dont start the joint_7 controller for a 6DOF robot * Changed the examples to use notifications to check whether an action is finished or not and removed the sleeps * Put back the homing script for Gazebo and removed the copyright notice since we don't use MoveIt anymore to home the arm * Adapt documentation for new simulation features * Updated the package.xml's with bumped versions and author and maintainer tags --- kortex_control/package.xml | 8 +- kortex_description/package.xml | 9 +- kortex_driver/CMakeLists.txt | 2 +- .../non-generated/kortex_arm_simulation.h | 41 +- .../non-generated/kortex_math_util.h | 7 + kortex_driver/package.xml | 9 +- kortex_driver/readme.md | 2 +- .../driver/kortex_arm_driver.cpp | 4 +- .../driver/kortex_arm_simulation.cpp | 535 +++++++++++++++++- .../non-generated/driver/kortex_math_util.cpp | 36 ++ kortex_examples/img/moveit.png | Bin 0 -> 30821 bytes kortex_examples/img/services_real_arm.png | Bin 0 -> 29748 bytes kortex_examples/img/services_sim.png | Bin 0 -> 33723 bytes kortex_examples/package.xml | 8 +- kortex_examples/readme.md | 57 +- ...ple_cartesian_poses_with_notifications.cpp | 2 - ...mple_cartesian_poses_with_notifications.py | 1 + .../full_arm/example_full_arm_movement.cpp | 68 ++- .../src/full_arm/example_full_arm_movement.py | 66 ++- .../launch/spawn_kortex_robot.launch | 131 ++--- kortex_gazebo/package.xml | 6 +- kortex_gazebo/readme.md | 25 +- kortex_gazebo/scripts/home_robot.py | 124 ++-- .../package.xml | 2 +- .../gen3_move_it_config/package.xml | 2 +- .../package.xml | 2 +- .../package.xml | 2 +- .../kortex_move_it_config/package.xml | 6 +- 28 files changed, 917 insertions(+), 238 deletions(-) create mode 100644 kortex_examples/img/moveit.png create mode 100644 kortex_examples/img/services_real_arm.png create mode 100644 kortex_examples/img/services_sim.png diff --git a/kortex_control/package.xml b/kortex_control/package.xml index 935cfab5..f937c188 100644 --- a/kortex_control/package.xml +++ b/kortex_control/package.xml @@ -1,12 +1,12 @@ kortex_control - 2.2.0 + 2.2.2 -

Gazebo Ros Control package for Kortex robots

-

This package contains launch and configuration files for the ros_control controllers for simulation

+

Gazebo ROS Control package for simulated Kortex robots

+

This package contains configuration files for the gazebo_ros_control controllers for simulation of Kortex arms

Alexandre Vannobel - + BSD catkin roslaunch diff --git a/kortex_description/package.xml b/kortex_description/package.xml index 5f0ba38b..018c38c1 100644 --- a/kortex_description/package.xml +++ b/kortex_description/package.xml @@ -1,12 +1,13 @@ kortex_description - 2.2.1 + 2.2.2 -

URDF Description package for Kortex-compatible robots

+

URDF and xacro description package for Kortex robots

This package contains configuration data, 3D models and launch files -for Kortex-compatible arms and grippers

+for Kortex arms and supported grippers

- + Alexandre Vannobel + BSD catkin roslaunch diff --git a/kortex_driver/CMakeLists.txt b/kortex_driver/CMakeLists.txt index f6f6b383..7e2c4752 100644 --- a/kortex_driver/CMakeLists.txt +++ b/kortex_driver/CMakeLists.txt @@ -17,7 +17,7 @@ if(NOT CMAKE_BUILD_TYPE) endif() ## find catkin and any catkin packages -find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs message_generation actionlib control_msgs urdf moveit_ros_planning_interface) +find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs controller_manager_msgs message_generation actionlib control_msgs urdf moveit_ros_planning_interface) find_package(Boost REQUIRED COMPONENTS system) file(GLOB_RECURSE generated_files RELATIVE ${PROJECT_SOURCE_DIR} "src/generated/robot/*.cpp" "src/generated/simulation/*.cpp") diff --git a/kortex_driver/include/kortex_driver/non-generated/kortex_arm_simulation.h b/kortex_driver/include/kortex_driver/non-generated/kortex_arm_simulation.h index 7bcbbf51..2124151d 100644 --- a/kortex_driver/include/kortex_driver/non-generated/kortex_arm_simulation.h +++ b/kortex_driver/include/kortex_driver/non-generated/kortex_arm_simulation.h @@ -15,10 +15,11 @@ // ROS #include +#include #include #include #include -#include +#include // MoveIt #include @@ -62,6 +63,12 @@ #include "kortex_driver/SendGripperCommand.h" #include "kortex_driver/ApplyEmergencyStop.h" +enum class ControllerType +{ + kTrajectory, // this is for the JointTrajectoryController + kIndividual // this is for the individual JointPositionController's +}; + class KortexArmSimulation { public: @@ -98,10 +105,24 @@ class KortexArmSimulation // Publishers ros::Publisher m_pub_action_topic; + std::vector m_pub_position_controllers; // Subscribers ros::Subscriber m_sub_joint_trajectory_controller_state; ros::Subscriber m_sub_joint_state; + ros::Subscriber m_sub_joint_speeds; + ros::Subscriber m_sub_twist; + ros::Subscriber m_sub_clear_faults; + ros::Subscriber m_sub_stop; + ros::Subscriber m_sub_emergency_stop; + + // Service clients + ros::ServiceClient m_client_switch_controllers; + ControllerType m_active_controller_type; + std::vector m_trajectory_controllers_list; + std::vector m_position_controllers_list; + std::vector m_velocity_commands; + kortex_driver::Twist m_twist_command; // Action clients std::unique_ptr> m_follow_joint_trajectory_action_client; @@ -114,6 +135,8 @@ class KortexArmSimulation // Arm information std::string m_arm_name; std::vector m_arm_joint_names; + std::vector m_arm_joint_limits_min; + std::vector m_arm_joint_limits_max; std::vector m_arm_velocity_max_limits; std::vector m_arm_acceleration_max_limits; float m_max_cartesian_twist_linear; @@ -148,6 +171,7 @@ class KortexArmSimulation // Threading std::atomic m_is_action_being_executed; std::atomic m_action_preempted; + std::atomic m_current_action_type; std::thread m_action_executor_thread; // MoveIt-related @@ -155,7 +179,6 @@ class KortexArmSimulation std::unique_ptr m_moveit_gripper_interface; // Subscription callbacks and data structures with their mutexes - // void cb_joint_trajectory_controller_state(const control_msgs::JointTrajectoryControllerState& state); void cb_joint_states(const sensor_msgs::JointState& state); sensor_msgs::JointState m_current_state; bool m_first_state_received; @@ -165,17 +188,23 @@ class KortexArmSimulation // Helper functions bool IsGripperPresent() const {return !m_gripper_name.empty();} void CreateDefaultActions(); - kortex_driver::KortexError FillKortexError(uint32_t code, uint32_t subCode, const std::string& description = "") const; - - // Executors - void JoinThreadAndCancelAction(); + bool SwitchControllerType(ControllerType new_type); void PlayAction(const kortex_driver::Action& action); + void JoinThreadAndCancelAction(); + kortex_driver::KortexError FillKortexError(uint32_t code, uint32_t subCode, const std::string& description = std::string()) const; kortex_driver::KortexError ExecuteReachJointAngles(const kortex_driver::Action& action); kortex_driver::KortexError ExecuteReachPose(const kortex_driver::Action& action); kortex_driver::KortexError ExecuteSendJointSpeeds(const kortex_driver::Action& action); kortex_driver::KortexError ExecuteSendTwist(const kortex_driver::Action& action); kortex_driver::KortexError ExecuteSendGripperCommand(const kortex_driver::Action& action); kortex_driver::KortexError ExecuteTimeDelay(const kortex_driver::Action& action); + + // Callbacks + void new_joint_speeds_cb(const kortex_driver::Base_JointSpeeds& joint_speeds); + void new_twist_cb(const kortex_driver::TwistCommand& twist); + void clear_faults_cb(const std_msgs::Empty& empty); + void stop_cb(const std_msgs::Empty& empty); + void emergency_stop_cb(const std_msgs::Empty& empty); }; #endif //_KORTEX_ARM_SIMULATION_H_ diff --git a/kortex_driver/include/kortex_driver/non-generated/kortex_math_util.h b/kortex_driver/include/kortex_driver/non-generated/kortex_math_util.h index 9c94d61e..59b4c85d 100644 --- a/kortex_driver/include/kortex_driver/non-generated/kortex_math_util.h +++ b/kortex_driver/include/kortex_driver/non-generated/kortex_math_util.h @@ -12,6 +12,7 @@ */ #include +#include "kortex_driver/Twist.h" class KortexMathUtil { @@ -21,10 +22,16 @@ class KortexMathUtil static double toRad(double degree); static double toDeg(double rad); + static int getNumberOfTurns(double rad_not_wrapped); static double wrapRadiansFromMinusPiToPi(double rad_not_wrapped); + static double wrapRadiansFromMinusPiToPi(double rad_not_wrapped, int& number_of_turns); static double wrapDegreesFromZeroTo360(double deg_not_wrapped); + static double wrapDegreesFromZeroTo360(double deg_not_wrapped, int& number_of_turns); static double relative_position_from_absolute(double absolute_position, double min_value, double max_value); static double absolute_position_from_relative(double relative_position, double min_value, double max_value); + + // kortex_driver::Twist helper functions + static kortex_driver::Twist substractTwists(const kortex_driver::Twist& a, const kortex_driver::Twist& b); }; #endif \ No newline at end of file diff --git a/kortex_driver/package.xml b/kortex_driver/package.xml index 9ba05a33..757f4407 100644 --- a/kortex_driver/package.xml +++ b/kortex_driver/package.xml @@ -1,10 +1,12 @@ kortex_driver - 2.2.1 - THe kortex package that act as a robot's driver. + 2.2.2 + The package that acts as a robot's driver. Supports simulated and real Kortex robots. - + Hugo Lamontagne + Alexandre Vannobel + BSD @@ -13,6 +15,7 @@ rospy std_msgs control_msgs + controller_manager_msgs actionlib moveit_ros_planning_interface kdl_parser diff --git a/kortex_driver/readme.md b/kortex_driver/readme.md index 6e913b2b..7f2a5b69 100644 --- a/kortex_driver/readme.md +++ b/kortex_driver/readme.md @@ -51,7 +51,7 @@ The `kortex_driver` node is the node responsible for the communication between t - **arm** : Name of your robot arm model. See the `kortex_description/arms` folder to see the available robot models. The default value is **gen3**. - **dof** : Number of DOFs of your robot. The default value is for Gen3 is **7** and the default value for Gen3 lite is **6**. You will have to specify this value only if you have a Gen3 6DOF. - **vision** : Boolean value to indicate if your arm has a Vision Module. The default value is for Gen3 is **true** and the default value for Gen3 lite is **false**. You will have to specify this value only if you have a Gen3 6DOF without a Vision Module. This argument only affects the visual representation of the arm in RViz. -- **gripper** : Name of your robot arm's tool / gripper. See the `kortex_description/grippers` folder to see the available end effector models (or to add your own). The default value is **""**. For Gen3, you can also put **robotiq_2f_85**. For Gen3 lite, you need to put **gen3_lite_2f**. +- **gripper** : Name of your robot arm's tool / gripper. See the `kortex_description/grippers` folder to see the available end effector models (or to add your own). The default value is **""**. For Gen3, you can also put **robotiq_2f_85** or **robotiq_2f_140**. For Gen3 lite, the default (and only) gripper is **gen3_lite_2f**. - **robot_name** : This is the namespace in which the driver will run. It defaults to **my_$(arg arm)** (so "my_gen3" for arm="gen3"). - **prefix** : This is an optional prefix for all joint and link names in the kortex_description. It is used to allow differentiating between different arms in the same URDF. It defaults to **an empty string**. **Note** : Changing the prefix invalidates the MoveIt! configuration, and requires modifying said configuration, plus the .yaml files with harcoded joint names. - **ip_address** : The IP address of the robot you're connecting to. The default value is **192.168.1.10**. diff --git a/kortex_driver/src/non-generated/driver/kortex_arm_driver.cpp b/kortex_driver/src/non-generated/driver/kortex_arm_driver.cpp index deaa7aab..3a8f3697 100644 --- a/kortex_driver/src/non-generated/driver/kortex_arm_driver.cpp +++ b/kortex_driver/src/non-generated/driver/kortex_arm_driver.cpp @@ -668,13 +668,15 @@ void KortexArmDriver::registerSimulationHandlers() base_services_simulation->StopActionHandler = std::bind(&KortexArmSimulation::StopAction, m_simulator.get(), std::placeholders::_1); // Other services base_services_simulation->PlayCartesianTrajectoryHandler = std::bind(&KortexArmSimulation::PlayCartesianTrajectory, m_simulator.get(), std::placeholders::_1); - base_services_simulation->SendTwistCommandHandler = std::bind(&KortexArmSimulation::SendTwistCommand, m_simulator.get(), std::placeholders::_1); base_services_simulation->PlayJointTrajectoryHandler = std::bind(&KortexArmSimulation::PlayJointTrajectory, m_simulator.get(), std::placeholders::_1); base_services_simulation->SendJointSpeedsCommandHandler = std::bind(&KortexArmSimulation::SendJointSpeedsCommand, m_simulator.get(), std::placeholders::_1); base_services_simulation->SendGripperCommandHandler = std::bind(&KortexArmSimulation::SendGripperCommand, m_simulator.get(), std::placeholders::_1); base_services_simulation->StopHandler = std::bind(&KortexArmSimulation::Stop, m_simulator.get(), std::placeholders::_1); base_services_simulation->ApplyEmergencyStopHandler = std::bind(&KortexArmSimulation::ApplyEmergencyStop, m_simulator.get(), std::placeholders::_1); + // Uncomment this SendTwistCommand handler to use the twist command simulation - not stable + // base_services_simulation->SendTwistCommandHandler = std::bind(&KortexArmSimulation::SendTwistCommand, m_simulator.get(), std::placeholders::_1); + // Prospects //SendSelectedJointSpeedCommand //PlaySelectedJointTrajectory diff --git a/kortex_driver/src/non-generated/driver/kortex_arm_simulation.cpp b/kortex_driver/src/non-generated/driver/kortex_arm_simulation.cpp index 1d44c1c1..59df4430 100644 --- a/kortex_driver/src/non-generated/driver/kortex_arm_simulation.cpp +++ b/kortex_driver/src/non-generated/driver/kortex_arm_simulation.cpp @@ -17,14 +17,19 @@ #include "kortex_driver/ActionEvent.h" #include "kortex_driver/JointTrajectoryConstraintType.h" #include "kortex_driver/GripperMode.h" +#include "kortex_driver/CartesianReferenceFrame.h" #include "trajectory_msgs/JointTrajectory.h" +#include "controller_manager_msgs/SwitchController.h" +#include "std_msgs/Float64.h" #include #include #include #include +#include + #include #include @@ -35,27 +40,36 @@ namespace static constexpr unsigned int FIRST_CREATED_ACTION_ID = 10000; static const std::set DEFAULT_ACTIONS_IDENTIFIERS{1,2,3}; static constexpr double JOINT_TRAJECTORY_TIMESTEP_SECONDS = 0.01; + static constexpr double MINIMUM_JOINT_VELOCITY_RAD_PER_SECONDS = 0.001; } KortexArmSimulation::KortexArmSimulation(ros::NodeHandle& node_handle): m_node_handle(node_handle), m_map_actions{}, m_is_action_being_executed{false}, m_action_preempted{false}, - m_first_state_received{false} + m_current_action_type{0}, + m_first_state_received{false}, + m_active_controller_type{ControllerType::kTrajectory} { // Namespacing and prefixing information ros::param::get("~robot_name", m_robot_name); ros::param::get("~prefix", m_prefix); // Arm information + urdf::Model model; + model.initParam("/" + m_robot_name + "/robot_description"); ros::param::get("~dof", m_degrees_of_freedom); ros::param::get("~arm", m_arm_name); ros::param::get("~joint_names", m_arm_joint_names); ros::param::get("~maximum_velocities", m_arm_velocity_max_limits); ros::param::get("~maximum_accelerations", m_arm_acceleration_max_limits); - for (auto s : m_arm_joint_names) + m_arm_joint_limits_min.resize(GetDOF()); + m_arm_joint_limits_max.resize(GetDOF()); + for (int i = 0; i < GetDOF(); i++) { - s.insert(0, m_prefix); + auto joint = model.getJoint(m_arm_joint_names[i]); + m_arm_joint_limits_min[i] = joint->limits->lower; + m_arm_joint_limits_max[i] = joint->limits->upper; } // Cartesian Twist limits @@ -135,12 +149,42 @@ KortexArmSimulation::KortexArmSimulation(ros::NodeHandle& node_handle): m_node_h CreateDefaultActions(); // Create publishers and subscribers + for (int i = 0; i < GetDOF(); i++) + { + m_pub_position_controllers.push_back(m_node_handle.advertise( + "/" + m_robot_name + "/" + m_prefix + "joint_" + std::to_string(i+1) + "_position_controller/command", 1000)); + } m_pub_action_topic = m_node_handle.advertise("action_topic", 1000); m_sub_joint_state = m_node_handle.subscribe("/" + m_robot_name + "/" + "joint_states", 1, &KortexArmSimulation::cb_joint_states, this); m_feedback.actuators.resize(GetDOF()); m_feedback.interconnect.oneof_tool_feedback.gripper_feedback.resize(1); m_feedback.interconnect.oneof_tool_feedback.gripper_feedback[0].motor.resize(1); + m_sub_joint_speeds = m_node_handle.subscribe("in/joint_velocity", 1, &KortexArmSimulation::new_joint_speeds_cb, this); + m_sub_twist = m_node_handle.subscribe("in/cartesian_velocity", 1, &KortexArmSimulation::new_twist_cb, this); + m_sub_clear_faults = m_node_handle.subscribe("in/clear_faults", 1, &KortexArmSimulation::clear_faults_cb, this); + m_sub_stop = m_node_handle.subscribe("in/stop", 1, &KortexArmSimulation::stop_cb, this); + m_sub_emergency_stop = m_node_handle.subscribe("in/emergency_stop", 1, &KortexArmSimulation::emergency_stop_cb, this); + + // Create service clients + m_client_switch_controllers = m_node_handle.serviceClient + ("/" + m_robot_name + "/controller_manager/switch_controller"); + + // Fill controllers'names + m_trajectory_controllers_list.push_back(m_prefix + m_arm_name + "_joint_trajectory_controller"); // only one trajectory controller + m_position_controllers_list.resize(GetDOF()); // one position controller per + std::generate(m_position_controllers_list.begin(), + m_position_controllers_list.end(), + [this]() -> std::string + { + static int i = 1; + return m_prefix + "joint_" + std::to_string(i++) + "_position_controller"; + }); + + // Initialize the velocity commands to null + m_velocity_commands.resize(GetDOF()); + std::fill(m_velocity_commands.begin(), m_velocity_commands.end(), 0.0); + // Create and connect action clients m_follow_joint_trajectory_action_client.reset(new actionlib::SimpleActionClient( "/" + m_robot_name + "/" + m_prefix + m_arm_name + "_joint_trajectory_controller" + "/follow_joint_trajectory", true)); @@ -420,9 +464,21 @@ kortex_driver::SendTwistCommand::Response KortexArmSimulation::SendTwistCommand( action.handle.action_type = kortex_driver::ActionType::SEND_TWIST_COMMAND; action.oneof_action_parameters.send_twist_command.push_back(twist_command); - JoinThreadAndCancelAction(); // this will block until the thread is joined and current action finished - m_action_executor_thread = std::thread(&KortexArmSimulation::PlayAction, this, action); + // Convert orientations to rad + m_twist_command.angular_x = m_math_util.toRad(m_twist_command.angular_x); + m_twist_command.angular_x = m_math_util.toRad(m_twist_command.angular_y); + m_twist_command.angular_x = m_math_util.toRad(m_twist_command.angular_z); + // Fill the twist command + m_twist_command = twist_command.twist; + + // If we are already executing twist control, don't cancel the thread + if (m_current_action_type != kortex_driver::ActionType::SEND_TWIST_COMMAND) + { + JoinThreadAndCancelAction(); // this will block until the thread is joined and current action finished + m_action_executor_thread = std::thread(&KortexArmSimulation::PlayAction, this, action); + } + return kortex_driver::SendTwistCommand::Response(); } @@ -448,8 +504,21 @@ kortex_driver::SendJointSpeedsCommand::Response KortexArmSimulation::SendJointSp action.handle.action_type = kortex_driver::ActionType::SEND_JOINT_SPEEDS; action.oneof_action_parameters.send_joint_speeds.push_back(joint_speeds); - JoinThreadAndCancelAction(); // this will block until the thread is joined and current action finished - m_action_executor_thread = std::thread(&KortexArmSimulation::PlayAction, this, action); + // Fill the velocity commands vector + int n = 0; + std::generate(m_velocity_commands.begin(), + m_velocity_commands.end(), + [this, &action, &n]() -> double + { + return m_math_util.toRad(action.oneof_action_parameters.send_joint_speeds[0].joint_speeds[n++].value); + }); + + // If we are already executing joint speed control, don't cancel the thread + if (m_current_action_type != kortex_driver::ActionType::SEND_JOINT_SPEEDS) + { + JoinThreadAndCancelAction(); // this will block until the thread is joined and current action finished + m_action_executor_thread = std::thread(&KortexArmSimulation::PlayAction, this, action); + } return kortex_driver::SendJointSpeedsCommand::Response(); } @@ -560,6 +629,50 @@ void KortexArmSimulation::CreateDefaultActions() m_map_actions.emplace(std::make_pair(zero.handle.identifier, zero)); } +bool KortexArmSimulation::SwitchControllerType(ControllerType new_type) +{ + bool success = true; + controller_manager_msgs::SwitchController service; + service.request.strictness = service.request.STRICT; + if (m_active_controller_type != new_type) + { + // Set the controllers we want to switch to + switch (new_type) + { + case ControllerType::kTrajectory: + service.request.start_controllers = m_trajectory_controllers_list; + service.request.stop_controllers = m_position_controllers_list; + break; + case ControllerType::kIndividual: + service.request.start_controllers = m_position_controllers_list; + service.request.stop_controllers = m_trajectory_controllers_list; + break; + default: + ROS_ERROR("Kortex arm simulator : Unsupported controller type %d", int(new_type)); + return false; + } + + // Call the service + if (!m_client_switch_controllers.call(service)) + { + ROS_ERROR("Failed to call the service for switching controllers"); + success = false; + } + else + { + success = service.response.ok; + } + + // Update active type if the switch was successful + if (success) + { + m_active_controller_type = new_type; + } + } + + return success; +} + kortex_driver::KortexError KortexArmSimulation::FillKortexError(uint32_t code, uint32_t subCode, const std::string& description) const { kortex_driver::KortexError error; @@ -571,11 +684,13 @@ kortex_driver::KortexError KortexArmSimulation::FillKortexError(uint32_t code, u void KortexArmSimulation::JoinThreadAndCancelAction() { + // Tell the thread to stop and join it m_action_preempted = true; if (m_action_executor_thread.joinable()) { m_action_executor_thread.join(); } + m_current_action_type = 0; m_action_preempted = false; } @@ -589,6 +704,7 @@ void KortexArmSimulation::PlayAction(const kortex_driver::Action& action) start_notif.action_event = kortex_driver::ActionEvent::ACTION_START; m_pub_action_topic.publish(start_notif); m_is_action_being_executed = true; + m_current_action_type = action.handle.action_type; // Switch executor on the action type switch (action.handle.action_type) @@ -618,8 +734,8 @@ void KortexArmSimulation::PlayAction(const kortex_driver::Action& action) kortex_driver::ActionNotification end_notif; end_notif.handle = action.handle; - // Action was cancelled by user - if (m_action_preempted.load()) + // Action was cancelled by user and is not a velocity command + if (m_action_preempted.load() && action.handle.action_type != kortex_driver::ActionType::SEND_JOINT_SPEEDS) { // Notify ACTION_ABORT end_notif.action_event = kortex_driver::ActionEvent::ACTION_ABORT; @@ -666,10 +782,17 @@ kortex_driver::KortexError KortexArmSimulation::ExecuteReachJointAngles(const ko "Error playing joint angles action : action contains " + std::to_string(constrained_joint_angles.joint_angles.joint_angles.size()) + " joint angles but arm has " + std::to_string(GetDOF())); } + // Switch to trajectory controller + if (!SwitchControllerType(ControllerType::kTrajectory)) + { + return FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE, + kortex_driver::SubErrorCodes::METHOD_FAILED, + "Error playing joint angles action : simulated trajectory controller could not be switched to."); + } + // Initialize trajectory object trajectory_msgs::JointTrajectory traj; traj.header.frame_id = m_prefix + "base_link"; - traj.header.stamp = ros::Time::now(); for (int i = 0; i < constrained_joint_angles.joint_angles.joint_angles.size(); i++) { const std::string joint_name = m_prefix + "joint_" + std::to_string(i+1); //joint names are 1-based @@ -687,8 +810,11 @@ kortex_driver::KortexError KortexArmSimulation::ExecuteReachJointAngles(const ko trajectory_msgs::JointTrajectoryPoint endpoint; for (int i = 0; i < constrained_joint_angles.joint_angles.joint_angles.size(); i++) { + // If the current actuator has turned on itself many times, we need the endpoint to follow that trend too + int n_turns = 0; + m_math_util.wrapRadiansFromMinusPiToPi(current.position[m_first_arm_joint_index + i], n_turns); const double rad_wrapped_goal = m_math_util.wrapRadiansFromMinusPiToPi(m_math_util.toRad(constrained_joint_angles.joint_angles.joint_angles[i].value)); - endpoint.positions.push_back(rad_wrapped_goal); + endpoint.positions.push_back(rad_wrapped_goal + double(n_turns) * 2.0 * M_PI); endpoint.velocities.push_back(0.0); endpoint.accelerations.push_back(0.0); } @@ -803,11 +929,31 @@ kortex_driver::KortexError KortexArmSimulation::ExecuteReachJointAngles(const ko // Send goal control_msgs::FollowJointTrajectoryActionGoal goal; + traj.header.stamp = ros::Time::now(); goal.goal.trajectory = traj; m_follow_joint_trajectory_action_client->sendGoal(goal.goal); - // Wait for goal to be done, or for preempt to be called (check every 10ms) - while(!m_action_preempted.load() && !m_follow_joint_trajectory_action_client->waitForResult(ros::Duration(0.01f))) {} + // Wait for goal to be done, or for preempt to be called (check every 100ms) + while(!m_action_preempted.load()) + { + if (m_follow_joint_trajectory_action_client->waitForResult(ros::Duration(0.1f))) + { + // Sometimes an error is thrown related to a bad cast in a ros::time structure inside the SimpleActionClient + // See https://answers.ros.org/question/209452/exception-thrown-while-processing-service-call-time-is-out-of-dual-32-bit-range/ + // If this error happens here we just send the goal again with an updated timestamp + auto status = m_follow_joint_trajectory_action_client->getResult(); + if (status->error_string == "Time is out of dual 32-bit range") + { + traj.header.stamp = ros::Time::now(); + goal.goal.trajectory = traj; + m_follow_joint_trajectory_action_client->sendGoal(goal.goal); + } + else + { + break; + } + } + } // If we got out of the loop because we're preempted, cancel the goal before returning if (m_action_preempted.load()) @@ -841,6 +987,14 @@ kortex_driver::KortexError KortexArmSimulation::ExecuteReachPose(const kortex_dr } auto constrained_pose = action.oneof_action_parameters.reach_pose[0]; + // Switch to trajectory controller + if (!SwitchControllerType(ControllerType::kTrajectory)) + { + return FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE, + kortex_driver::SubErrorCodes::METHOD_FAILED, + "Error playing pose action : simulated trajectory controller could not be switched to."); + } + // Get current position sensor_msgs::JointState current; { @@ -861,12 +1015,12 @@ kortex_driver::KortexError KortexArmSimulation::ExecuteReachPose(const kortex_dr m_fk_solver->JntToCart(current_kdl, start); { - ROS_INFO("START FRAME :"); - ROS_INFO("X=%2.4f Y=%2.4f Z=%2.4f", start.p[0], start.p[1], start.p[2]); + ROS_DEBUG("START FRAME :"); + ROS_DEBUG("X=%2.4f Y=%2.4f Z=%2.4f", start.p[0], start.p[1], start.p[2]); double sa, sb, sg; start.M.GetEulerZYX(sa, sb, sg); - ROS_INFO("ALPHA=%2.4f BETA=%2.4f GAMMA=%2.4f", m_math_util.toDeg(sa), m_math_util.toDeg(sb), m_math_util.toDeg(sg)); + ROS_DEBUG("ALPHA=%2.4f BETA=%2.4f GAMMA=%2.4f", m_math_util.toDeg(sa), m_math_util.toDeg(sb), m_math_util.toDeg(sg)); KDL::Vector axis; - ROS_INFO("start rot = %2.4f", start.M.GetRotAngle(axis)); + ROS_DEBUG("start rot = %2.4f", start.M.GetRotAngle(axis)); } // Get End frame @@ -875,12 +1029,12 @@ kortex_driver::KortexError KortexArmSimulation::ExecuteReachPose(const kortex_dr KDL::Frame end(end_rot, end_pos); { - ROS_INFO("END FRAME :"); - ROS_INFO("X=%2.4f Y=%2.4f Z=%2.4f", end_pos[0], end_pos[1], end_pos[2]); + ROS_DEBUG("END FRAME :"); + ROS_DEBUG("X=%2.4f Y=%2.4f Z=%2.4f", end_pos[0], end_pos[1], end_pos[2]); double ea, eb, eg; end_rot.GetEulerZYX(ea, eb, eg); - ROS_INFO("ALPHA=%2.4f BETA=%2.4f GAMMA=%2.4f", m_math_util.toDeg(ea), m_math_util.toDeg(eb), m_math_util.toDeg(eg)); + ROS_DEBUG("ALPHA=%2.4f BETA=%2.4f GAMMA=%2.4f", m_math_util.toDeg(ea), m_math_util.toDeg(eb), m_math_util.toDeg(eg)); KDL::Vector axis; - ROS_INFO("end rot = %2.4f", end_rot.GetRotAngle(axis)); + ROS_DEBUG("end rot = %2.4f", end_rot.GetRotAngle(axis)); } // If different speed limits than the default ones are provided, use them instead @@ -1048,13 +1202,122 @@ kortex_driver::KortexError KortexArmSimulation::ExecuteSendJointSpeeds(const kor "Error playing joint speeds action : action contains " + std::to_string(joint_speeds.joint_speeds.size()) + " joint speeds but arm has " + std::to_string(GetDOF())); } - // TODO Handle constraints and warn if some cannot be applied in simulation - // TODO Fill implementation to move all actuators at given velocities + // Switch to trajectory controller + if (!SwitchControllerType(ControllerType::kIndividual)) + { + return FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE, + kortex_driver::SubErrorCodes::METHOD_FAILED, + "Error playing joint speeds action : simulated positions controllers could not be switched to."); + } + + // Get current position + sensor_msgs::JointState current; + { + const std::lock_guard lock(m_state_mutex); + current = m_current_state; + } + + // Initialise commands + std::vector commands(GetDOF(), 0.0); // in rad + for (int i = 0; i < GetDOF(); i++) + { + commands[i] = current.position[m_first_arm_joint_index + i]; + } + std::vector previous_commands = commands; // in rad + std::vector velocity_commands(GetDOF(), 0.0); // in rad/s + std::vector previous_velocity_commands(GetDOF(), 0.0); // in rad/s + std::vector stopped(GetDOF(), false); + + // While we're not done + while (true) + { + // If action is preempted, set the velocities to 0 + if (m_action_preempted.load()) + { + std::fill(m_velocity_commands.begin(), m_velocity_commands.end(), 0.0); + } + // For each joint + for (int i = 0; i < GetDOF(); i++) + { + // Calculate real position increment + // This helps to know if we hit joint limits or if we stopped + { + const std::lock_guard lock(m_state_mutex); + current = m_current_state; + } + + // Calculate permitted velocity command because we don't have infinite acceleration + double vel_delta = m_velocity_commands[i] - previous_velocity_commands[i]; + double max_delta = std::copysign(m_arm_acceleration_max_limits[i] * JOINT_TRAJECTORY_TIMESTEP_SECONDS, vel_delta); + + // If the velocity change is within acceleration limits for this timestep + double velocity_command; + if (fabs(vel_delta) < fabs(max_delta)) + { + velocity_command = m_velocity_commands[i]; + } + // If we cannot instantly accelerate to this velocity + else + { + velocity_command = previous_velocity_commands[i] + max_delta; + } + + // Cap to the velocity limit for the joint + velocity_command = std::copysign(std::min(fabs(velocity_command), double(fabs(m_arm_velocity_max_limits[i]))), velocity_command); + + // Check if velocity command is in fact too small + if (fabs(velocity_command) < MINIMUM_JOINT_VELOCITY_RAD_PER_SECONDS) + { + velocity_command = 0.0; + commands[i] = current.position[m_first_arm_joint_index + i]; + stopped[i] = true; + } + // Else calculate the position increment and send it + else + { + commands[i] = previous_commands[i] + velocity_command * JOINT_TRAJECTORY_TIMESTEP_SECONDS; + stopped[i] = false; + + // Cap the command to the joint limit + if (m_arm_joint_limits_min[i] != 0.0 && commands[i] < 0.0) + { + commands[i] = std::max(m_arm_joint_limits_min[i], commands[i]); + velocity_command = 0.0; + } + else if (m_arm_joint_limits_max[i] != 0.0 && commands[i] > 0.0) + { + commands[i] = std::min(m_arm_joint_limits_max[i], commands[i]); + velocity_command = 0.0; + } + + // Send the position increments to the controllers + std_msgs::Float64 message; + message.data = commands[i]; + m_pub_position_controllers[i].publish(message); + } + + // Remember actual command as previous and actual velocity command as previous + previous_commands[i] = commands[i]; + previous_velocity_commands[i] = velocity_command; + } + + // Sleep for TIMESTEP + std::this_thread::sleep_for(std::chrono::milliseconds(int(1000*JOINT_TRAJECTORY_TIMESTEP_SECONDS))); + + // If the action is preempted and we're back to zero velocity, we're done here + if (m_action_preempted.load()) + { + // Check if all joints are stopped and break if yes + if (std::all_of(stopped.begin(), stopped.end(), [](bool b){return b;})) + { + break; + } + } + } return result; } -// TODO Fill implementation kortex_driver::KortexError KortexArmSimulation::ExecuteSendTwist(const kortex_driver::Action& action) { kortex_driver::KortexError result; @@ -1068,9 +1331,202 @@ kortex_driver::KortexError KortexArmSimulation::ExecuteSendTwist(const kortex_dr } auto twist = action.oneof_action_parameters.send_twist_command[0]; - // TODO Handle constraints and warn if some cannot be applied in simulation - // TODO Fill implementation to move simulated arm at Cartesian twist + // Switch to trajectory controller + if (!SwitchControllerType(ControllerType::kIndividual)) + { + return FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE, + kortex_driver::SubErrorCodes::METHOD_FAILED, + "Error playing joint speeds action : simulated positions controllers could not be switched to."); + } + + // Only mixed frame is supported in simulation + if (twist.reference_frame != kortex_driver::CartesianReferenceFrame::CARTESIAN_REFERENCE_FRAME_MIXED) + { + return FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE, + kortex_driver::SubErrorCodes::INVALID_PARAM, + "Error playing twist action : only mixed frame is supported in simulation."); + } + + // Get current position + sensor_msgs::JointState current; + { + const std::lock_guard lock(m_state_mutex); + current = m_current_state; + } + // Initialise commands + std::vector commands(GetDOF(), 0.0); // in rad + for (int i = 0; i < GetDOF(); i++) + { + commands[i] = current.position[m_first_arm_joint_index + i]; + } + std::vector previous_commands = commands; // in rad + std::vector previous_velocity_commands(GetDOF(), 0.0); // in rad/s + std::vector stopped(GetDOF(), false); + kortex_driver::Twist twist_command = m_twist_command; + kortex_driver::Twist previous_twist_command; + + // While we're not done + while (ros::ok()) + { + // If action is preempted, set the velocities to 0 + if (m_action_preempted.load()) + { + m_twist_command = kortex_driver::Twist(); + } + + // Calculate actual twist command considering max linear and angular accelerations + double max_linear_twist_delta = JOINT_TRAJECTORY_TIMESTEP_SECONDS * m_max_cartesian_acceleration_linear; + double max_angular_twist_delta = JOINT_TRAJECTORY_TIMESTEP_SECONDS * m_max_cartesian_acceleration_angular; + kortex_driver::Twist delta_twist = m_math_util.substractTwists(m_twist_command, previous_twist_command); + + // If the velocity change is within acceleration limits for this timestep + if (fabs(delta_twist.linear_x) < fabs(max_linear_twist_delta)) + { + twist_command.linear_x = m_twist_command.linear_x; + } + // If we cannot instantly accelerate to this velocity + else + { + twist_command.linear_x = previous_twist_command.linear_x + std::copysign(max_linear_twist_delta, delta_twist.linear_x); + } + // same for linear_y + if (fabs(delta_twist.linear_y) < fabs(max_linear_twist_delta)) + { + twist_command.linear_y = m_twist_command.linear_y; + } + else + { + twist_command.linear_y = previous_twist_command.linear_y + std::copysign(max_linear_twist_delta, delta_twist.linear_y); + } + // same for linear_z + if (fabs(delta_twist.linear_z) < fabs(max_linear_twist_delta)) + { + twist_command.linear_z = m_twist_command.linear_z; + } + else + { + twist_command.linear_z = previous_twist_command.linear_z + std::copysign(max_linear_twist_delta, delta_twist.linear_z); + } + // same for angular_x + if (fabs(delta_twist.angular_x) < fabs(max_angular_twist_delta)) + { + twist_command.angular_x = m_twist_command.angular_x; + } + else + { + twist_command.angular_x = previous_twist_command.angular_x + std::copysign(max_angular_twist_delta, delta_twist.angular_x); + } + // same for angular_y + if (fabs(delta_twist.angular_y) < fabs(max_angular_twist_delta)) + { + twist_command.angular_y = m_twist_command.angular_y; + } + else + { + twist_command.angular_y = previous_twist_command.angular_y + std::copysign(max_angular_twist_delta, delta_twist.angular_y); + } + // same for angular_z + if (fabs(delta_twist.angular_z) < fabs(max_angular_twist_delta)) + { + twist_command.angular_z = m_twist_command.angular_z; + } + else + { + twist_command.angular_z = previous_twist_command.angular_z + std::copysign(max_angular_twist_delta, delta_twist.angular_z); + } + + // Cap to the velocity limit + twist_command.linear_x = std::copysign(std::min(fabs(twist_command.linear_x), fabs(m_max_cartesian_twist_linear)), twist_command.linear_x); + twist_command.linear_y = std::copysign(std::min(fabs(twist_command.linear_y), fabs(m_max_cartesian_twist_linear)), twist_command.linear_y); + twist_command.linear_z = std::copysign(std::min(fabs(twist_command.linear_z), fabs(m_max_cartesian_twist_linear)), twist_command.linear_z); + twist_command.angular_x = std::copysign(std::min(fabs(twist_command.angular_x), fabs(m_max_cartesian_twist_angular)), twist_command.angular_x); + twist_command.angular_y = std::copysign(std::min(fabs(twist_command.angular_y), fabs(m_max_cartesian_twist_angular)), twist_command.angular_y); + twist_command.angular_z = std::copysign(std::min(fabs(twist_command.angular_z), fabs(m_max_cartesian_twist_angular)), twist_command.angular_z); + + // Fill current joint position commands KDL structure + KDL::JntArray commands_kdl(GetDOF()); + Eigen::VectorXd commands_eigen(GetDOF()); + for (int i = 0; i < GetDOF(); i++) + { + commands_eigen[i] = commands[i]; + } + commands_kdl.data = commands_eigen; + + // Fill KDL Twist structure with Kortex twist + KDL::Twist twist_kdl = KDL::Twist(KDL::Vector(twist_command.linear_x, twist_command.linear_y, twist_command.linear_z), + KDL::Vector(twist_command.angular_x, twist_command.angular_y, twist_command.angular_z)); + + // Call IK and fill joint velocity commands + KDL::JntArray joint_velocities(GetDOF()); + int ik_result = m_ik_vel_solver->CartToJnt(commands_kdl, twist_kdl, joint_velocities); + if (ik_result != m_ik_vel_solver->E_NOERROR) + { + ROS_WARN("IK ERROR = %d", ik_result); + } + + // We need to know if the joint velocities have to be adjusted, and by what ratio + double ratio = 1.0; + for (int i = 0; i < GetDOF(); i++) + { + // Calculate permitted velocity command because we don't have infinite acceleration + double vel_delta = joint_velocities(i) - previous_velocity_commands[i]; + double max_delta = std::copysign(m_arm_acceleration_max_limits[i] * JOINT_TRAJECTORY_TIMESTEP_SECONDS, vel_delta); + + // If we cannot instantly accelerate to this velocity + if (fabs(vel_delta) > fabs(max_delta)) + { + ratio = std::max(ratio, fabs(vel_delta / max_delta)); + } + } + + // Command the velocities + // For each joint + for (int i = 0; i < GetDOF(); i++) + { + // Calculate position increment + commands[i] = previous_commands[i] + joint_velocities(i) / ratio * JOINT_TRAJECTORY_TIMESTEP_SECONDS; + + // Cap the command to the joint limit + if (m_arm_joint_limits_min[i] != 0.0 && commands[i] < 0.0) + { + commands[i] = std::max(m_arm_joint_limits_min[i], commands[i]); + } + else if (m_arm_joint_limits_max[i] != 0.0 && commands[i] > 0.0) + { + commands[i] = std::min(m_arm_joint_limits_max[i], commands[i]); + } + + // Send the position increments to the controllers + std_msgs::Float64 message; + message.data = commands[i]; + m_pub_position_controllers[i].publish(message); + + // Check if joint is stopped or not + stopped[i] = fabs(joint_velocities(i)) < MINIMUM_JOINT_VELOCITY_RAD_PER_SECONDS; + + // Remember actual command as previous + previous_commands[i] = commands[i]; + previous_velocity_commands[i] = joint_velocities(i); + } + + // Put current values to previous + previous_twist_command = twist_command; + + // Sleep for TIMESTEP + std::this_thread::sleep_for(std::chrono::milliseconds(int(1000*JOINT_TRAJECTORY_TIMESTEP_SECONDS))); + + // If the action is preempted and we're back to zero velocity, we're done here + if (m_action_preempted.load()) + { + // Check if all joints are stopped and break if yes + if (std::all_of(stopped.begin(), stopped.end(), [](bool b){return b;})) + { + break; + } + } + } + return result; } @@ -1163,3 +1619,30 @@ kortex_driver::KortexError KortexArmSimulation::ExecuteTimeDelay(const kortex_dr } return result; } + +void KortexArmSimulation::new_joint_speeds_cb(const kortex_driver::Base_JointSpeeds& joint_speeds) +{ + kortex_driver::SendJointSpeedsCommandRequest req; + req.input = joint_speeds; + SendJointSpeedsCommand(req); +} + +void KortexArmSimulation::new_twist_cb(const kortex_driver::TwistCommand& twist) +{ + // TODO Implement +} + +void KortexArmSimulation::clear_faults_cb(const std_msgs::Empty& empty) +{ + // does nothing +} + +void KortexArmSimulation::stop_cb(const std_msgs::Empty& empty) +{ + Stop(kortex_driver::StopRequest()); +} + +void KortexArmSimulation::emergency_stop_cb(const std_msgs::Empty& empty) +{ + ApplyEmergencyStop(kortex_driver::ApplyEmergencyStopRequest()); +} diff --git a/kortex_driver/src/non-generated/driver/kortex_math_util.cpp b/kortex_driver/src/non-generated/driver/kortex_math_util.cpp index 4f140ce0..e89552bd 100644 --- a/kortex_driver/src/non-generated/driver/kortex_math_util.cpp +++ b/kortex_driver/src/non-generated/driver/kortex_math_util.cpp @@ -22,17 +22,32 @@ double KortexMathUtil::toDeg(double rad) return rad * 180.0 / M_PI; } +int KortexMathUtil::getNumberOfTurns(double rad_not_wrapped) +{ + // it is between + return 0; +} + double KortexMathUtil::wrapRadiansFromMinusPiToPi(double rad_not_wrapped) +{ + int n; + return wrapRadiansFromMinusPiToPi(rad_not_wrapped, n); +} + +double KortexMathUtil::wrapRadiansFromMinusPiToPi(double rad_not_wrapped, int& number_of_turns) { bool properly_wrapped = false; + number_of_turns = 0; do { if (rad_not_wrapped > M_PI) { + number_of_turns += 1; rad_not_wrapped -= 2.0*M_PI; } else if (rad_not_wrapped < -M_PI) { + number_of_turns -= 1; rad_not_wrapped += 2.0*M_PI; } else @@ -44,16 +59,25 @@ double KortexMathUtil::wrapRadiansFromMinusPiToPi(double rad_not_wrapped) } double KortexMathUtil::wrapDegreesFromZeroTo360(double deg_not_wrapped) +{ + int n; + return wrapDegreesFromZeroTo360(deg_not_wrapped, n); +} + +double KortexMathUtil::wrapDegreesFromZeroTo360(double deg_not_wrapped, int& number_of_turns) { bool properly_wrapped = false; + number_of_turns = 0; do { if (deg_not_wrapped > 360.0) { + number_of_turns += 1; deg_not_wrapped -= 360.0; } else if (deg_not_wrapped < 0.0) { + number_of_turns -= 1; deg_not_wrapped += 360.0; } else @@ -75,3 +99,15 @@ double KortexMathUtil::absolute_position_from_relative(double relative_position, double range = max_value - min_value; return relative_position * range + min_value; } + +kortex_driver::Twist KortexMathUtil::substractTwists(const kortex_driver::Twist& a, const kortex_driver::Twist& b) +{ + kortex_driver::Twist c; + c.linear_x = a.linear_x - b.linear_x; + c.linear_y = a.linear_y - b.linear_y; + c.linear_z = a.linear_z - b.linear_z; + c.angular_x = a.angular_x - b.angular_x; + c.angular_y = a.angular_y - b.angular_y; + c.angular_z = a.angular_z - b.angular_z; + return c; +} \ No newline at end of file diff --git a/kortex_examples/img/moveit.png b/kortex_examples/img/moveit.png new file mode 100644 index 0000000000000000000000000000000000000000..f7572df531ca82fd67a37d6e85e48f4364dd5fea GIT binary patch literal 30821 zcmeFZWn9!>*FFk}geVdMA`;T!h_up5OG^nzOAjED(xVuFh;(;%cdCTa9YZPIAss4SMM>t$r5l$pFfgvj$x1%Pz`!2G zz`zv8!vVjst^JI^z@WpBlYF4=s=pSGJ9x7tyrQG^85Qh-j{+fm8`%@-QA4U=DWdBU z7O%e1`|Xl`;BvprY<~L_m-efR0XHw>jDNv~eSY={Gn$TDr{o*%@nZg@&_>}9&w$8) zh}z`N;Qi@fUbUaY4tA9_)0>(@0vXDQqLZq07?^nC7+6F;7})>zUswd5#|2nElP&M7 z|M8c9ecp$~r%9UbKYbN^An6Jg9@M5OmF?dj`ukNxqwjzJ|KDDViC6Xj1D1cqmG{km zek}$T71#eZWPUulqH@fjjQ?XY|GZ1wkOAj^yzG4Vy*QZI75qQ?uKk~eIQuRhwE2G- z4mO<5r)d~RIOgGhFe3W9u)yp8)3*Pbx;Pa!(J0(UM(sZ?04A6W@rD0oDi*IXuym=m zEH3@)QU7yr*!;%-%W$x4h{O%8FVHC7`p;Gbi+cIoD*xjX|8Y@s6n;=m?@NbgwoN>G zXn450%v5}hrAN~oSj`4x^@p4He@ApreR!u*16&CpI-**8CKKL}26;8 z|BzHOEtalE%IlYZneZ9&R%qf;bLByY!AVH94JR+_%*8Z{Dy}vUJRRkl1T1=!zCdLRtv^(} zr}*?GPOdGSLHtOgJKdAn*E@H8y4PF_JEw^kuL+WUn%*{P${O}r-of^F#q4gmEBO5l#!1&jhWIks zr1$$0hSq(QynmicWDz8;Ziw0r@)njbM;?o!)@G%HXeJj?*=m_JBl_-L-W9zM391hk zVmbS+lP)hLdV5vQg~->8nZ@QS*Wbp{Ep14l)}2gyxm>%ySlDow6U%QCqw73oI{rGw zVU=EA`~`pT2D^gKer}P29#?FqR_yiCj!<#pJqqj!VG&7#zjjGBJ}>F$U@(mjleE;H z?6}Lc=j26-r@iKJvmb@Jv&A@igm*rSgBef0zAE|zrO=_YH{sADis;9Ks%0qHzd{ zD?j5qekBxQM5cR{+r@cROnaf=*J-`>lWDz2i;VbmHJ{o`Rf6?- ziMfdwF>nz(`gwJ7>*v?WD*M@z3y>r!I0aG1x6;mfEQM|PceLI|_LUnotK@y2%DZgd z{suf^-xEnjh(_J$Z`bgDFWZYOp#0Vp&V07@Gz6bT-TWO5@FIcd=$ZubS)mH$WUGN4 zC&RV$m&HQq_@8|v+B;ZGM42Y6=9PX7Z6br@7B z;NxAoo#Nbp?f+g3yTZd$((W(cW5eealv3A|lBf}X^K;Sj2!pE z&ms%FRjiEERTc5{Y9Z6w4}F~KgxJd=fRZvRY^e>uXsKRIsI_etMvj`C)DCIt=0_m3 zlnv#_&D*!2I_u!&FE|^IUM#$n6siy<*M)Lb?#~3E3U8|^d)o=?D#}Bk&J&LX8NMC;$Pl)6JL^NG-c9Cd#SWXbT!Pr zqM1Z~uz_1OCm3JnVO2YOZk79H{Rn~m-lR+7>PTTCh5ha#sj_gewqXF0ukEHo)yu{B z5!#%srPQGA-bkbeYA#gyFe-|1X6z|rn$%U{Z}j`~Oa3)_>7JN!?S|tvm6H=-GAsAx z=+uhm>-sRuFK>s)-^uoT=9%3!W}c`=8m%DC^YeSeeP%?q$j`FoCoNA_rz^DLL`SAg z6B`6j{ddEC(iCd;xjXhnefY1o6txzoM;p8KKEORVzL@GhoP8XjYrFhLD=?Y9_8LQ= z%@9d>4oC=2F?juMa%kTiSN)n+>P}inbE7qU^%-2%Yx5@-LS- z2Jxh&@H|8cuZc zy<=VPM@9YwuPveKo!`m*^j73&B2UUh))a1rL5y?lTV$cTq=7cEV+8iug61_JZ2xzZ{@*<4v+kN zN4uePe?APZGTRp9B8D34FmW zYU+9ZUNmH*gPFeUfs_yu+ri9(FWAgOk)x@d9QdwX{3zv`yVpn${me|Wy%E$Dm%4Ct zPqI&TA7>Ur}JOjotAW`K zd@g>j3wvn?Bej@h+gKCfvDB}bNtzn5r3LV>q0^ViT~-r`^NbBf!`v%tcy?p^O5i@C6sxEG2WT&v!a;l&u=U8Ykf}+UDWs6-PqtE8l=m-K~+r| zFIQP~LXZz~E1y+`e`Q!fFj38zjEsju65=T-zJEwR7?ad6z1bQ$&K{uHz+0^5DSs`H zAYbkXgqZFX^A!rPJILE25@JbN=}(A8V;nMZejf}z;+WVs@S!(0W&${!8KgffF}z>q z?G9#;IlMrCbCqVT6i(y%1Cz69(qpH~w#f%`>am|N`sCBK&M!Y&P9gam)|WBwT-q&| zTbQblVTKipV8VQm(iCanwTyZ^o*E_XBvr7LP2YFeZ#?A+thjgDIcZ#xuTqB7Xe)URA)haW?d8t*EfyF6hfoe^2oP%huF!j2`o7oc>s-uO^ z5$jJ1|0%p_yN!0!poS??tw(4!Dn~YRQ(GlLEAB7Gl?LIvEo)J7 zKYMS`&P=R?%ObnAzv0rj8kwL&jVhhGx#n(KaODQ?H-eWWdyH_)329HJz*|(iq>1i2 z?jB^)c}Qvwm9x-|0-4xM%+3b z`*}f*(haeY{6w=hYm3|sC$_7{SIyMv(bKZ@>WWDHkSq%GfTjq3c#Z+*`f>UpW0a8q z-al@=#c1+7nFaGq!p81z@R4j`H086DOO}jU!jD?9j?{COo8VM@hx6pEnhs2He+3ck zJB-vD=$G_+YGyz#FgPC6S<>47tcaB)gcVEa;{Yz}1-$TPFSu?luFXpU&+#TRXl3%KNE`P8Vxh$+X?1OE|8++gBDMi1Yj z?Imc0DhthF@O85! zUc-p^f5NmAJm3TFA6LbIg%HW2u#Da9*-~%o+{3CCrcNL%@Lo;=RG43 zNR1BDwer}}F~p6@EsEu@AfimvE0+OM6!$w0keQ2&6knIpSn%eky#=69IbUp)efogUIj&JwR-1tGwjnscDE^lD2ha#FumG@1<4wpv? z4Xmk;r*C0dL2-%7CRCfQggd1l5A>e$QOlo@sD@fG#o6Pys7d&J&88cX(o_mz96VFhP0692}4?! z)(`a$_T+wCH;>F{WcN$XZ=Dv}techMJDzya0pWwryl;wN_FozCYop(bM7nm<^?J-w zZG4g-+@?*mZ>3c9t~Pp?&Nvylt9P`cW#Boa7|Y)Usa-2MxS{`LN~gY&H-;Tc7yklg z=-*pSB}n|KVZiXX;p;0_(JTazG8MJ=pf2a74!cCOFNUQ(vspf(pX+DkGWF7&UIM!U zDUlmI+HssN(lFZ^=peLFmFoTjhU*~%VtNFXkaOO+(L3rx$2_$V4QKET0pn&o&J?+$ z${vBSXQVDG*_nd)U5DxIpblFd*0mFJk+EzZ9|mwM$Dgt442|TE#*|N{tYfL z(SgG@Af}MwwytyyNMaeg^FTpOLf70Zj>j9&NMYbn%$%dmtjsV#JPLP#!l92gILEZT zPf^n@2HwZz?)yLAdCu|;Kl$pp6FcpARb*Esr77bo?v)#J-sqw#rU?l$6TxG#yU@|Q ziCuY(g;g{DN@H))m8SbKVr25F_r8RH$NqB`)j}=#Qj|Q$Q=(CwWNE5Dxi%&q_9MFd zCUQRSZ=Y`Q6+>eBRKVIMjo#%D$CBIL>+wD*WzL!OK0S`klQ!(|)u!E1=>@M|{*9giQeZEMs8*Nvwi6DZfQ`MaODGu(!>T8$#tkQU&n@}so=UkRsILHEwwM>V6)6HDtxGx0H7oYGvE(S=O|NQu)%?SgY zmOK z6bu7sdqdO(PNUyUGEhQ|P`Imq1%wqM)|m(7qu;Tg(8GnfYmQ$WfQqEr`)HQd7Hmj| zoo=DR)8tNBAEuO_QWxbVclN$BMLwNzp7z|UVYw#HSPM$BN!!|WP14Z>w-q+;_YcbG zicEJDiF=ryfqyZ}|JqSHbSllSp#)~TlA&c-x=XR2lw)|admd+ldbWV+)bnV&&1>L! z*T|zvYycG1cIg3B!1ic=djsS8>U~oxLs7&9N&qv-)uU>>@f+ z7(LB19?D*ca4LK#6}0Gqjd%GQa-A%;aN9%0*cYb&8QSHyE$frs02R4~mEGfuHolyg zx#OsBmb6^;*RAi5qBB^p!-2#aJI__!4LfgCY%M@aCe|ybH$b|7BQvmr?Npvl{-_?z zq1+R`0pJ)(-E zrF3J+Q*z9@-57vZlUKDjI4xx!7|P50yZu#uKuEztR+yTwPu;y!bcKpPk2we6Kw<-H zwaWs5`4sYG^{)IR-^wV0l_Cd2I;6<8(|T?)b*|TLHe_R00IW+8pO2k{Zpa`t<;r*S zSQ~yc$i+YJ)+a?#EwVQ;pyz#zuK{(g_svyDE6?C;F%mnD%hU*9DfZ>#bCLYRIvAobE|-uzUB#ob2BC z^vSSdGIv06>(eoJFg4ivW%Dx*sNa}h#+2<-xE7tiV3{5 zDd)5kueV=6Z}08bLjr?%G@9J{9aLCF(0(p|H9ZNRwbTeXX5N#&XM3R7kyIA;*f^~H zhIQUg<=%l8ITpoG5lH@1u-x_E(({<`KX?Pro&Zps6}_%H)Smzv5uR%LBtnn*fx@xO zMTm9ghia1`kzqD>8TTBU+Vu+2Qb|hYz;+V(+dm_;%_v>AKI5W9!WW`UKGqC%Wi0LM zNIL^av6_Ihu6G?ApbhzBX^rw#13ducT5ogR?UR|b%FWlLngs`;0~#}y1I zn`n~C6_%f=M#!Y^Y|LgowH>)w9^7$J^NZ52XHk{j^6yDQYySawS5qV?Z~WfjyO+=t zcYmWNusC+5QSPQ%Mjt*)+>eiFiv%D%@*6x9oHAfPeLRdqwc*SayHl{_5bwb(V1&_pMjrQ`r7hjdVrx z>r97#q1jO|apJ2bhIbOg1&+{8UOk{JHfiZyIv;5;rTh!Tc7(RtI~unvq4lzXBXb=j zqdi;02Og#L=%$Q;ea1A)==# zxT88mqKhBYey=2@vsDB+`ZeBtqdL0n6Kj^|hM;y0v3Go&L1EAvZ+8)_8llrOLZMdF z)bV#N(Mt;O{7>un&-D_XWgcgkCbwUs5_HTm@V^d$_o51FH-1r?>fEuy()Ca-$-|08 zvJWIYtDJJn9e)<8c*rXTAj%^z89_gFRMQY?e+eGc9yR4UdxbMf?#DRrxQYGkS!)OD zxf8%wOqd^9LgVjbndbJ<-%{$(;}a{sCf4RsHUd9;D`s|B^lH!t!m?)}| zFD8*cek5efRn=_b1hu(YRvCxX3>DAt992&MW>qkuD{?w8&ik zkXQkPL9rA!7D1}#W!33O)D*>K5~q|B2S6>IZbLQaIOIcsXziKZ%lh2sgS0 z>p+5)pm4Hka8;&hflliUPF!loPiTbyxC+jqByY!Lm}5a(aT|=c+<~c&-%mVqlhYLw zOZALKpyI;$ZB9Csd+2>kAP|FDmy}K-LYKsPTc_rp>y}}nrBf@VIU}LNw_ES_p|>G^ zgL0`PO&hhFqMSu+Ulme^072B;;DAIdQcrZdS6`Zjq*oATO z(ZSDX?yaC6sWUzDSROLJ7vc^A(Q%{GjU1%=z#{wMQw7H=A72^2ckRyyKI4G%y0lVN z%AxN84%`HiozPSQj5@7!;1&==XOeGA1n<(!iXZ73l*!@o-0V29vPzSccP zbFKwAKYF48;Yb%dhIiu`b1z$?We=C1JiE^DSk_JNqixYtB^EDqz|&V5kV_PNsdjw3 zW+|oI^wV$jrG((aY3d@B603)G3a^~Hgaz7qIOa_N&?+_;+UIPw0CVGAk{ zbF6&<^CZVezq73o@%^Iu+uv*>k;NPI*2o`y5DUfL(&g75?2g3Pj^ym=b^F?w{4%X_ zjqR*r=Xe_hIiDxd(%DH<%NX;h^C*@_rKaN_ zZ|<1GV*g!J0TBei2XV(V*OC?t^2XBy&Z5KxkUd1$wfaEH~oDaV8Ap1?M*lCPhIw1 z8l%y4R%+b?ACS_&F6RpzQN_r(btIgfA(h7O$A05@u!1vdbC5045vXtGUBbb#Ez`p zm>Qa`MrdB<()~TU-ZN`Eo6?K$vwE#^y~E|#o8i3sZVpO#(nZNSX-a=aCz`&%4F9`8 zI$Kr_=U!$i%%g}vit-&m(a(4Alud2fSk5ql*il;<`RJ-oKDutMCtusBkBV`?s6=h@UO1O$#CX8H1r$$FM(~=v!pd?()FS z`lqQ^bWO)hcmlh1#4o1|0460Ghw(>C;SYo}n!>a6(myU%;pOZ`hl?k0HfgtIc-doD zHC_W~_yFmd3L+vwi0|)-F#??lfQ}#hizZOH1SB@;&q<~KEX)g1aYK&E(;}LG`2?&L zl)dkXej5}6_647=i0oq&=6UE`q6fN{J73H#et)Ky1AND=WuTMvpNI6uqJJLP?EI4q zI);JLTE?E|`nffznZeMEeq8>854r_|k8rxh-~X3SyS)QHZ|=uL{~2rnvAE&t4L6+g zc#(7gyhsou`quf_e8daEd{z;7hA01QCYTlYIk&<)n)>|3M0l^jbBS!5@Xp77i5?i2 z=t<3=eNMD5fQikYf_ZKecJxC^T%xJ|Jj53~gzjV0<=+pv1s;N@Dfrhz-je|J5Y73} zvbcfS*xe(m&ldv&CJy8}7iaJ~&$T{DL|}Q|7^eRv?t!s_fz14OAm?VL!}za7{_7+E z-8KJ>Bmduxtlu;YOK~&VFPPYND<+CkU&bW*;YQGePkk4*n$P#`DQ&(zhb~7!(2JLs zVfjx_zUZ9C#u9Kkq7zv{7$l5NTpX{3v;_|H>Ahi45HwsBo=-L+Q!NZ6dUw2yey7f3 zc-QEQwwq$R@J+M3UfVxO_(E%Rz+h*+W#=yWbA+a`S9f;0S0oHd>&1~dU37k&!yLh} z+i#x|;qVc6w&)9nx9@yVUH<3Bb>cS$?ne*p0=*^nh_H0;i}((mr?h1fK%q7prjhTz6pDBySGG1LyW_#~<7mEEozDgi4%A`7dK&8v0>vkUZU1Rp zzD=4+SB?1259M{VO7)$7Q2F`-K^LF~W&xHe60aY)`6K4ACc%D-|xaY1l8 zFW*zmC2%jA1oYP#Mh;N!^{=OZb}QBeL`b~;aKLRms8oOYrWv*%f<9+;X@54z&J5t7 zRkQGh1t3>2&Up9;E51hbag0QH7^rX_si>c$NJ(M9tdEu}Hm*;8$2DolY>>CaKH z1So}U%IBT{tW=sAK?^*=7}kKYrc%^NbpOYNJ+y?bu<-;ADeHZRrYqznPevL~hP*{j zk9KMSPtgyEMX2Y>t)g(g$GJu>U|{zkdKCVikidv0y+YyrAFnq6Jhra3h}N1N9(21j z%ob(?$UW1#dx^ZUK(VR~r?qk3@!o&*I!)Zj_qL74$c?vDwp(LX9C<|#=}~f_%xHa{ z?c2?df-9^p{c4%(niZz!zY5Oe`WbZxT4yBf?3IQ!`tLTg2@Yk>%L0*4CvW1POo^o#O*9KPd< zTR?2Qw4pAvxMczuVF?X}1B!#w<(xE->l{W@baHpN!aM-|r<76&fk0w`+9Hbd>WzeZIXDi!w^`|!FL;d{U>-8%Of+kq{O{mco?!AG3<+HojLG}tN zUZH{Y!PmvDV}LoF1p1;__yo{xeSs7=lbp1OdaW#?1#u@QdyTb#1MTZV^JNoN_FnkQ zz<0G*PxC9MUJ%@=N)lR(bC|%yz3I~w5hF|%K;N6anokC^0o>dREubOI&-R7l-*I0n zeuqLH+BMj#OLhgVT6}tm0Xab;68z1k@ycb>nZfGs^Yzc_k<7=jLh)2=D&R%Ka zG4$=2B7j7eYhr|7mQWNI0`f@!c+RloW)5(xbY`M$g>o~8_`6207Bi2T7XeaO6Z~t` zBE>tg|tEl)Y{Bj-GE;(-lPs9*vEjGi=82T_?@=hS> zv~K>?J+oN&6%Qx@!LdpjpZvX-1lEeE~_4{KToRrW9?@Z&3bw|IfE(2qoT_4!KXt0&Fi7aF2Hzs05 zuH;7fX9J5jbiH#t9oKHpe$xgN1aIA1NylLvops_e1yO`lWY~cjB4oiC@V$e`ma_Y- z4qXeqtQQKW-c04Mrv4I0c*XL5`Vx-9-ucn$7!FENt?fwbEhUlb90O3m?jSSWto*c7 zDQ=UFiXLrAoPNojPomIwHA-X#IB_KvkU$#z+6D6c4s-9DUi&{c!qk+qhX!a=b$*eP zEfI~jlO<}DR;Z2W(tsT{#Hb^-+biK&qx*6`+>>8-h9c%iomc$!6xB*)w+0w>{! z-Nlx&&6L8CUls!7l{$)&FJ}VQ}+_G ze9}eNdND}j2Q?=g8w1E&e6a<`BfA=S3P`$nKYID~vc`^-tgNhmHtWz;#49sRh?u0Z zGv^}hQV$q6GZ~JR$Ow2{Usp17DZ{IB!}>Eu({DV6T@g&Zf1}Ig1(>=Q*tN$AN?Q6a z(-VEUpOI@n3x)^GgJz85WNea|JO!ZX47|?uWwV?)84A>n`X2^<;w~n7HyGT=N%0Kb zeOL<=yH!By-A`aeav9CbHAcpowtz+#DzV*&KyjAB$}H1-JgDFaV^h)Pn2;Z-4dnt)Sd@l4UmK)~jLv9VbYb(a=Bi$cdakX!Ujlw(65C`J{i?=g znc`YIG$6u4B#@X^W={$t5MD$fa_zw@UG<_|mZBCQp{6D~4Rg}6BOELE=xx5^L?2NC zmp(qk{#AA7=O57RA(KxNd5$?&SuWMpRzMLXPNL;V-k^7cr?Dr-w*;gUg2A6wSgjQ^ zUw88kD4h7#D+)|HzO9MyOYSUx@EYeO7h2WuOa3u9fRrjHoyUjx>4WTKY5c8geg>&5 zOc6Lcb~KXM?UIrieyH>_k(;)ptWcUALIClwb&Y9+cB??>e#RRAcy3-hmM(88~uGDl!ZIp?rUxzerr$qfY{chtbf~e9zoK8StBB@A@;i*47r*D9-)!uIQD}PNfyYY zW`re61Y-U(=PF5GR+CwZ)~@)gG}8M_!fdk&V-?P<4@8I`jTs20(YgKbfm>60?5bQ4 z;(Z{`zdomI+G}~ULnSo7&pw2EXszi&ASGGPT9}$pRnuYr_e{a4&n43#B}k&t7Y(Xm zd9}g?9U+R84(I6Q(k&3YMdsF=GuvO=*JAJ31c{x2^BTYG98ZhW(gUQ5dR`j{Va1wy zSz6{vLQF&DE~}A8V{_meR6sT9<6617@)Gbs1R_<)bbjYN`us{P1|^Zwgq9oa&FUJxAtRw`F3h&oH&MNiJ7*Bj zY=xqKq`o5g{dJ-*JHBZ<9#1X8E<7z%d^Rz+;811U!qe}mGf7tS9Z&O=$ipmwxA?|Z zg|w@>iEY)7=tA$A&B|U5pmqDi`w<_;Pl3p7*sX@5v*_ca(1qcZsQhLLniCt-r|>cv zjK=b|pyBg{^;M*Eg>`wUOa+{G) zI5y7I*-Dj#>HBi;O4w=&HEy`J*Y)Wez+J_3&NN@>Vgz(ARU_>)FIJQ}EVr!YQ;o>P zxL!(E((mAqh*lPI-km}85f-YzXDU^MVbtftxQ5P8@NzC9{hBoCCI}t#Nv|ck&fqsb zQxH3oiwu@=va7<@K_=p4U09F2Y%&ET>1d(V$qv!Qirj*l_VuE#gxScAeh+04gnA|D z6uF0Q)!uZl_4O*cCu_-(echo)WW@Yqd_xAhp(itNu3StrHDtIEf~(?lrPkgP`+ahO z93J#kdLUp#Cfc|>A%8#rlKwNo^C1p;4o4@<+73tw-zyLOj0BWo4ItwNdg`Zs6`ePv zjc8jWznK8iaV-IzezSzE*PyYg6<+QD*GRC9C)qx zVQMe*t<0_=dCl+v1a76##-%k3G5l`o}L`@D01YBt=)jzw^1KI0K~L?%jMZ6 zAxP?=iyW42!uC*JVcO*iw48t%2n!T1R@l$B-tUr9XajPZhU0a+z35zgzq39+bcYkp zngQduq)og-9kk3O|l%);jeMSOT83v?A z=G%d7oW5t7wEPx?U4f!e4oG>|5T z*xP@`&Ib&6%Q~n_y?|b}lQb9IRaJ$qwl~n()#RP}-TnTwv!wJ!rDj%YC z``1_avrH@Gnk+T@55HpPg6jIKP1Vo0Jnz-f4S4}~YO+czdq~YXfdUBKU?+R6 z@mXp^BhddGIrcYOJvAICH=U_C%yPN1B9xoE`nCD}JsCtJXeFx!tz=`~WEAf}3?a6W@XvtP`{2t2)84P1r6y4)dhO1aVf{K${~x2vqT9Neempeim0>)iiX6-)kZ*Wvj0r7Cq~f*sox7ZLRFTmd3Q;qqiHNP zD3okL|J?@My3h#-`0}TlbXW?rCELms3lYEai&HDI;^79M_OS)txkpugdN|VP3}*9j zvkkkVZ08$8mg`;HL}LcbTku+Jntuse3FC%o`);eWG&Iv9Y^27F8V|bc;V4&6NF-|PLc^8STX=4eNUCnaF zV7C=>QM5=6xzoD*r$KYHL{dcZCYJE{kP#5k77;;pPdjB0c#ntIS zQpkfA+o!ZlO|Sg$vE8;0vmVm@sAP8yzJJ~=3*^G{*!-Z1h6S3xwU|yvmnL0er$-yQ z(}xiTHPzjMtNRo`EQ0Bh(qHI^l6z7PCn%9@tdNmngk4NiVB{d-EmKhBoJY$zL!Xp@ zqPg?a#ms@pe=A~7O!esBHw$nmiyov+YqghHJ8~PqU(VU%Z=qeX4C|pIqp5iGXaz{* zhZ`QP24yulqnpG+aqa51TXn=<<6b=zC;zJK^ad47q^m=bD_9KQOHUj1bqv|*$Xt+VmC#m*5;@olLiulHF z+0V!sW_dLo3}J-Rq4aj8v=We5w0TxMfk*yyL+n;Zbl0Drpu7^z0@nM`9Z?i{DGNQdYFty zjR^We8TlgWzpXy^we#AE6^)gZUn^_WD6{a(JyelaL{HWK_PRx)u|Pyq%SC>_3PHsk zv?#sjt$M~YM_R7hJGb@Ag$I!YyjXp%<)m)q*t$S!sX-oXJjid_Lz26W2Sv+Zp_Q3l@SIb^~WTf^-IwDU3z%nYU*)r3{A}gpVOe4 z2ldBX+q$UB%fGqR=lIy1MPm;zby70Yt+tIbQGv8#Q=C`wwbn2$)Vo^C#YTL{7|Uh5 z3R?$Z&I#yb>rf#7&};NMKEk{tD0@q1m!vTAW&OVORenezs^|2mN0fykhZaK3m#m`g zX}K6IgZJxS;X?J@O$!|VVgR6xCpvNz^T$x%=rSyI6#;ejG3*v%W+=kI+Pf08mP~;2 z(EWstm^z^d9JMGjZR2ukSl0$cpGeP){y0cQCV_ZyP3m4eBOF8tWCG!BIfp_(=r1Dr z8io$`=(ctD{K59iTqfB%lHrsII`UR06l=+EwwvFj(mZ!=phnxmiq-EdmkHB0#k%&iX}D_lN26GBwXFo(6#YlZ~HbG)&bL zmAlN?ZpM@^HbV(r(drN=KTVnut6_Pn4$OhZ%f#^2QxYFNu3K@?OKpD-q;7nY7G|uX~^I3smv0MnY~_IihyX{#i=9d`iv`_FCn{tJH#n zn`2oaQicO3&hW+pRk_t^GyBIGn;<##ZC#{j+NE69LlZRXE zlHG7>&pG^WuhEub2KkB0VSNgSj>MHqDFKHAc;#~n@2<*v2!W1jRNRCmeFQdUJ&`<} zN<}wXqi#^65vI!Ar|7wKO$z^|j#ADsJZv&WjW|@lVfBGs8SXd;X-EP3biuRyzfTi2h~@n%oO zRh+~8td3E8J%jdeif~4l4H|dt5vym?2_(;s==|UalYWJxMzR*DQ$+!!dw*JU?-Kq3$wb+7Y&?IS zpd~v02L@DlKVXV`z_HiR3saKrUymmZ^l`+|j|(wTm;`v0%D4W8<1^nV6y<#S~%{o#M+1p|mYeL&&6#D!>U; zkdk7`RE1XNuY8(K{8Z)AwexgnNiL_Pz{bkZs<;beG2!TJ(;T+)%m7k5{QWb@Kv?t* zh`lJnm2FmIBu{el_MU&*Nq;9(zIUuW>sd1RaE2jSp*Wq?E7aG%bV$<3RCKk7xTP9y z!Ew>AgUY5%bv;tB=4}|v>fyMa%j7)ITuO9qg@A=R^s1kH2&CTC(|0437x}Z2H!SPI zITxjkANI(QgJUjd6wr34gd-q|KR$7LdF?0|x8*r%N$T{4=aCT203H<1qMDNC<@XFx z4%ODBUix%%{oOr_UOLb{w521R-7w&M39h9&&BpUI^OF2?HO*M0@@)xF*`;3gvNU7x zvX*|od0vsT@_?e3+r98>1xUn=eki{E`iGP2=q?1V!Zgw@J@Csk9Ni1F+)HcY`5fTM zLqC=!SJ2mK*m2MiD~{Q1la`gwzf!^+W*h3eynz%}fv%RIDxV1cM1Gw9g18cKE|2L& z*Vsr(q{3C<>+j~Rj))_~epTR{R>+jC9f3NCzTH8yOzXJ>BthUbPCK^w)B^S)W}69BgSGS?ZSd3l$xqkNy?w)dRP zl@psFi?IVf(osnkx6ya_P|(8fV)WE7lywg^eL58Y6>OHo4Q1W2nRFUaEUz?j*Z*GV zG-PfTJKa9dnRl-Jp`!vrht|2(@Lz2;s;2!zk3xhR0T|D!L5;&}KO^Z~QXpAv zmbp{080?`NIoWv7&#G*26x?6@fBUZO%o}7Fezi~89(^s;y z>f2=ID-(EQ9wfN8_dsJ|6>#=yku7Q~J?B$rJhkUve^mZ>`s%@Xg*zvU0fWdyX>9rf z&Q|!t9|kre-hdcuTtiE59+a23E?s;hRW=o488}aH8J0>xlU=6B5;YY4Od<^xiJz58 z6ELpd&jdg$#5_r31I+{11^o5Q;6$YSfW8&Nf4z`=T1yczu<^M99A&j!CawES$$+za z6$_%fJ7_bRL`O(8yMjz|DRQDb9)BSGneff@E2k@O&t2iu1z^vcbjU{(XjicO%N0Hx zg_RFy$zB@>8VVSWY|5a`H92M+8k({Ox70M&0zz=2$mr|Dr&|(7mMNy}rn`30`{bq^ zUL5|nkAGu1Sm5DAbt)uOuD};m|M&vy5qy@y&H9L{=3U78*Z*;10?1uZY4An&w&6|9 z>py~uj)E)s_A5nFwyc8;mh!jlmS`Rta%8^yLzz3H@0pS)Y=i%LNE-3=&q}K9m$z~5 z4(|&%UIldNfW#lV8BJZmlSfQ!UMAyr{QQsO0#N<(t-RlAIBEcyt@o}LSJd_T&OiTS zrfXj7+XVG|Cs!sV@SyX%M88k|UP3T;=Ox4wU44r$FYcY-bD!H4*cC6_@N&5FZPp|J(+*bOShRL9)5wd2kd2 z7p3K2_(X~ITh6>I2tJ}8gt2h-pK~&cAN*{EiX1zCF$Rndt-1V(^WitVMF)m*5tjZ( zLW}|P22q#c#(8q`U*RSe(SN0^{}uQCSML1(L;%iVE*v%8ZYiRv^#-l<&*dgtAimXf z{N_0xOgsU77aftX|CK*sa0VRu?aPMxJ{`-IIok1y1kZ;?!(NI`7__g|uZ$*~-Ha$` z|5@QYIQfVdfp5HWQk3|*rF;KalPuS-F~^nrCCz>%{N#$K^H~$il75@$dC;U&!9@3? zXky53sWsVsuFdMlA@L4(F8ta!gtS{K;HN3H%z_-A8T}X^hu@ z?kRYWBEZt!vTYOpGa@hah$0dn?ejF*{X}K8laqLBAn#!5me*6AterJmzS(rS{pae% z^s~;b<>W9!to?j!rJN$aW`j5JtAIaUpWOP_kp6QIE;ebC9nzdvq7j5 zyOd)FeSaiYn+g4&IS8H2p*!s|a<-D&HM@qN#Cr&lZ}#?ozb5gl$^K#yw%D7J{dLe! zjJ(|=xSIDP+St$pOYGpg@abPPT(YJ~W;n3R@(Md~d+emoJK(?9bYQ8l)@G-&pDRd!(sf;{@}x3H8tE zvyLPPdIhl@xEIa=ats(d3A$6;Kki|yn)cD#rs4Q+)!@Fu3G~%`z$G1cKoTzy_Sr=} z0wupi$5jNb!9-t4DPNF8{M#Tt;^gQ>GNVka$tRZm6>AEyq?`sfkLgv;f)4EOXa&;= z3djjMA)rq;pK{wfAIK?xoJR240wl*iHgGJfQS-7Vxb@JZ6n){GvIAA7YD6U53v?+L z7&LnEl-aeA2ae?x@;X~WcPdY462BIDAvjzBiaJ6z8WP33qKxiToY{U+@$>Y}i^F_& zO$ziKSQ>tW3z)xqa`jEDw}@LY$p zC?fI;knkL>6iQW+=Ztfb@@1T!wpin!by~Hwt+}A_Xr9y4w+Y+`&{d>04jNon?o`i( zbb6KAGv&ks;Zk{epfO$TtoxUibxoY8wP02YsfTl*;dnZv*UZGqBiz-%a=qlGUkCbn zhEl~H-h>k|-_vRqtM|5c z0eAVNq)KL$Irji^M?WfLDXqeoy?bQ`=sp#!-xgBPs=bOB%WN3*)~WrF2_2|wR^xvJ z4RDD3MouQV%2m8C_ba_w(X;SXQ^fc6^n%V)f^=ttofD?XwnS2(|=3=_{+8Qr9| zWv=H%km|+5CHp0u%+DC$1#S>`xx`f-KO5%v%RGJ}R9z<^Ls|o=4X9l;rHo_sDEdhVZP{AMW$%C>@MC$Iq{HB5saUt zE(R|>vpGn@7QnwqR+5Z$ z%=fzWq0jR?$MYY2f1BfQ9rx|N?)%!#^ZkCEGMyXVSBYEdR?1uBS(F|6th8hn3{xEg zVwW!KHHCyp!5WD7(9AmSXg~JrDCQ^xe}sK-vM7};19868E3_a)z9`?&m4o8bYjWtd zP=vGRpy7an>YQ7%=Ddk<2H`23xkwL@O^$id>p*_Wme~5l=QMQ}?hutQG&5_%Z;m|7 z-51xBzkIwrH>A#~8;oP8rHYcu4R0pt&|iIj^o*B)zj0?jOsA2Umj`k;OnN3^|T+|`py2&i!uC5r($msk@b+Mq^tyE1po@j9+8C7~*-b3@%ekqDo& zMs*AWtC<4br7Pszr`Zh%$_+IsD`B(jiE{Tjxb$~e8CIJdPlekRF($vV1 zjNH zR!kx^!_VP>ek6WxXjNu?G)?_$t-eZHv4t& zQV+T{1^d1*?MS4+97(39i_L%G@D;s>mt-Tcvn`3O)wTRryOQR}b#k7(dURg%@#J6L z^(uW+RXvjh)%n-A&HLxg0E^TTRe$_~TxNV1TtqNVlK%W$uSzUK+=_}TT-vU6Su;`AuZ0a%8RCYP#PX-K=D8#) zpMOv&vh5EfTs~cSn7FUX%ywW+M>K3P9t@uOODjWuh{2Xjb74|#Wy4cfA}oH)5$(Y^ zGf$TN4(8085DW&wl%0sA$OLdHuL<$IQo?C&@CK|!Wd87SCp4h7nflt^&hEFWN;dB3gH_8)^7XZM@tK=j`Yz%gelxwArs zNlWoTL*MQ+(Hf6#4BOfx!{L7)wZVDXCkPrVDnX^WVosA|fbj7tab_|ftnP>f&OoM$ z?c0Cd5k0G8le+#yrApGaWGtB3QS^oW{3SGTNOn4=OOB4gN8#FRywW`8pSn7r<{`!& z$npx;{3J=N#^S_EIp3XPe2LW?4+wM|&bomaNP9p!G>oh4@Dm;f{FzZG9|O^0o~zO) z^}ym=eapn$Pysrj<}ylrs3^UeoHL@**nD3iM$B+`Z&_bmc+ z59hqEH8HaCg#7F zysbU-btuCDm|`9_fe5~VvHPVTEDt5?>@Z8jlYT&Z%4a)ZEZes6ut7BfHqHzg+#Bxg z-9wmUTYy=kRRF$ow~XGe(Vmj-`BXx&Q7HMNlO5lPNxE9X>U|bg&Ylfyk^+biyntSM*Jm4gDfmW1i~;W#n$5YXH7+3(e&3tj_{1X_XN;`qH>%BS9Gy1ni6&$ALhOy%y?kWV+uq>8v`vJrUleP?li$}(El_qn} z(7%BX{5oKY;U7Gne+Utn9st?W{~|DzM>ieB*Cw3om+2BpxFQ(6E1>vxIm?-PySYU` z1npHnrQA|Yi34F(uiM9iOA}|MLwkTFVSxT=Z{QmiQx~w+`*#P1P|l_U<8gpkjM346 zCF>d>kMMDWgiN%{WO;+LF5LwN>+U04Se-O>9OQ6V4P?wRmUBxm4YfcLpq!zJGkGS-zSUl^ckR21RLffP=j^9xXk0W%5U z!dxpI2C9KEcmV#^TgC4|+c}al8zHI@ki$L$g4x_onuEUfOLlpm!S9 zmhJcgCnY!007+IE>vN&5o`$+=%d(VY(nxUqCw9p$c=o5-+)j&$>V&6 zV}k2}=dE_Pz3SV{wQOS%ztnW}nuJn)MqVzNDA#{_A>0CDciRk#7nh6{Ya|M=o-z$D zlw*4C>JTVlw(cl+R)W)YalipfE~;`&w7xtm{qM$&F&JD#JL$xE9*4cJ9VoD`5LvMP z$IIQ{A?WzU!*1%sk|(h#P%_b;Y9n-0>|cw228mBt@`d)rEG2=4O1$Lh5XiXi1X6e5x~;X<|ENy6z8UQCJIbq9_OC!z2=4&Wa5 z_)h!@e1fyyCzw@;!>ti@J&Lo1GUJev!4H1M(u2V0-rZFJqO#B*ZyUUTQLd#Q25Fvv zwp;>&kE_Mq$cj(lMuwSFVeSyG{bP##v%IO6meP#`-U-$t0p$?qk9Qmh6>ecZq}#d5 z4Kpl!CUY@)DIV^S!U_(I@J5n#;ge0yWX0`mp4BNzLxl(P8i>^PvyPJIsiOv3;TG<=cY z->A|a@-%3@M2`5)6RA@nJ{>aJ5Q5G+%Ghc*eLY5A5qoP=De@>RO6~%fD8VW7G3}!A z+K*SmKrUoh{ABg6?oxQD8K&zQ;3+M?+B=$muPF1o2qsVbQ->~psr)1%S43c_CnQ8>CPA`<%^RlMa@g%U3A@p9&Tx#KocLph^I+V{C0B zQO~CJX!U@TgcnfwJqHrqeh4pDH5Lnby`BTR(U5e&-0nrNbk^cM2il~CfR2WyNM*+- zUcDJI`vdY74&>`%fv>?6HUr(7#q4&JhT9q9oI z9GHDOU=ZTw*$6Cq_G@BUKz2}uumrMmAImO(r&t{%>cEFkE6lZYXukfY_Mh|hK2fIN zr%gy)UwKMFUShr^03AmWKReGr;60P~KMOA~_e0CMdu>j_RVl(7LI3;u)ekH@K{6Yp z@;zWqMsT&F#tRzKxjxoCll~nf4Q}%PN4G}a#v6a01zj{}GYG5!Um*7)riKkydOOoK^=XrF@2b`++-~OVxugVB3t)Iz z*Fw;H>6*z-;y}blOD+PoiW%^UdyMC6enUK zTVh}ywNvTxuhC<^KY3(38wg}eVC8`mhxDagFymAwF@Uv=Ky30-0~L)Z7Y0ZT?|v5C zRs_n>wVy>|=)9#eAZ?a~tdz@pILvloU2wD6IYL>mPor98aT@YIza|EvdZG2?1{5&C z(*z7DT17I-fXU|*(%Vi@shSc zFDVtkK~c%+B4_s~c{isgyfC#(Mc(FCy)?}NFIQRUM&~v(63?u9sk#byP!_^Z_%UI!NdM>4#%4u<^2^6$lD2Pc6GhpX=)!?u zfe&EUB9?#ww%#J2(og*>SZD7L>EOe`_j}4%&Lb8nr%NXOb&>J*e2FtM;MXd!=yrDi zONwbqcc~eGt{!^Tz@X2r=ElLYXIcR7b!~i4{s+_QGz<0jmVy2Z!2$^Or-ap$ju0kj zwB$Vn+DAp8EVo1K5PDe1D9FHmi#wSgyB1fUtZ6Uw!gO=#uPffrhLJ}paVf))DaAl(tX0hhJ2WtrYni< zP+tF8hwN&0|JY2z7Le+@$Q&WIq%4I`_c+&N#Nszef9v-eHk8$QGf@B= zI|AH&L(;B#WUi6j%dB#^%r!}!z3E@n+$yHS;WBrnaVS?RRWjMu-Bdt*kW#e;% zN(XW<$lNx+FsVl_cKIFX_S4zPnx*8@cqBwLuKWya4Y%^s18PA<4+>g6{*=c==7W{` zhepkqQA0mo`#J_-(6cvU?24#sU}DQ8io~!WTas5|%v}NBJ>ADtSE%QVmQtUZFYlxt z-C_1PVzOt5xH$NwEtYP#0_7P2zX>e+ThSCvf4Dr}ALN&3ih8A2bl7rpfH%hAqR>TjTuqER1 z@^8do^CjMN(l2V?-ZM)XR6>tK^gfXnn0ZdEIqKn~J`=|pO>5`0ld>AvQ1 z^Llvvx40{}&kDFQYYYJ*(@z?V{?EV$tel<>_i+@nkc~#5tYQl?#@u0WxI0QMD#~gn zXF)^+Czl1Fx_39;W20Z$ksQI>(Hu4?zHRQL(7l2P7G$w>^mj1*&7aP?gXa-@-Z5UN zTE#FXT8O-aSkf0fodduc?mOHU#V^&cWYb7#kZB`&KTXhZVpRG7YNQ<LLWcZ{>;e)`mT`y3w6s=|_a_9_L zE0S9QE2)|5y_v21%6gZXd$Nn{@6f;Ol;59Yy+9Nn)3>v^9q;4uLcwGX<|v1QmdwfU za!2+F5Q;TX_As)Emm!auYENm=&BjfED|K!B=kB}>sucA66^hf%MU zVXNDW5&l)U(|5}{V+X#DKfV_UibXkID^no7M&(!$Wjw$C=Kbi?#UZVrpM6ltmd!5%z3J#J3Lia`wq31f;OLRoA4lUx)3=&a#jV zE=|KT^K-{{g$CnqVD?K3EX*YQko!YQG={1$`5_Y$)TeR`*sUPXH3*4X3sW@Pl{_wu zgXwXSxYx9D5Av^^fG@UHvX)coh6vssN4!!MwYdbIDF*8N5WXLfPf6$CD_1ZXPv)>& z0w=)__LBWM*telaIyyFRvaEf-F^Pp0J%3{oMW4_AHzW}RD?%im)U-}~q371Tkr|Zx zosE+FQn;xy1XMnKQ6{X1*r4WWv1x*~2n!Mq6RXHdYqGoZQ2nfOR1=37D12~gAW)ar zAA~kM5zg&2D|D(up-3IqWD=;sHPx^DU##ICqMu>D3&!q!4k~u&;r`=w`o%)=oo7}{ zpu@l)w4!9%0ZX^DcHxhN#Fl2Yw+(%`QuB+!MFBlIX5?DUtL;Az^bz?}o8u>b8gjmi zOHPP;kvDS+F&!3WL-S79gB-l8)6N%PaS%Zoh_$+w+WCIaxs=4r$IZbK10qVydnRwN zeH^&~gwqMXIfFc?O$YVVzJ`)bVLR-)(16;7kE`i>t~}sV45PYesTK`xV3CNXb$L~R za(F#I?fsDdJKepXdEhzuo>aRiwL1=#$M4emWafmjj+|a_M}osZ=8i*pTB4YiL<36|_y8`eY7hl8 z-^$$-1Ze#mx_J~G4wfIT9Q!7-u)k-~_U{>gFwhYE4}Kk`8Fr9eSGb`6tMNsxiOW(GGHnyN9Ry{t)&6JWUFO zmsoSO(AIr0fV;djLEIz!d1Oy{K?+ECLj*=IdCEWj=WQ%SXEVUHouaG{;sw;!Jnr0F zY;9^Bw(WfL*7bcx*7^HC#o2J)(K-BE`AYDzjl$Ky+{bA2SH9vRa6fq40E01!IN;-a zce`;(^oYs~$+h{;PMPpGZo61#ERS8kd$GOdEF1SD{ffX{)nVKu3j00*wV-WG%q(nm zuma%s6Db$BVi@Pj1d5E1hw`+|p>|?}pANIIZ8k*iHoB^Yd^F*9mvv_36mO8;RUPyZa(MsU^y59X7S=D#igmK+rgiLiwNjOzN$%Q{a~U>_12`^}xA31! zGC`MQl8pRujA?c8*u?p==-Fep%jo+H`czp{#{~cG9`J8|)C(Tj&32Sogf;D};dSI9Xtu3(9_3{bq?|rq-S204U90Y^w-?k@MHb1m z)pYZR+QXnb2)L*%Z1at5_Bh+G1N!9)$x|7yhE$K=#}M0 z@Bgoh-D4B&J9kIsPX}z>Uyq5^tn;e2#^yD)o_wERhShF%QqtCKw|=Owf`_?v^8X)Z h^NZi=nPbc&-IJqC{yUJ5K>6TpC=FfpC+Dp0{2$dCuz&yn literal 0 HcmV?d00001 diff --git a/kortex_examples/img/services_real_arm.png b/kortex_examples/img/services_real_arm.png new file mode 100644 index 0000000000000000000000000000000000000000..7bf79abd69ded63522fecd3632bada186a8a67ac GIT binary patch literal 29748 zcmeFZbyU>r*FFpg2!c`yB1lMxbV*7`N=bvXhzE@5F|T~>M^ zr-g-utBQq%{gwb9{7ZG`p%NAr1D2B9eVrGkh`Ec^H+84a_ihrhFt9vOe<_V?C;frV z|GRRiS$+&HWp=@-~)(u|J@)NsCDGp@$PQOMy8<&nqUz`pvR@Dg^+@co3N zR^OR(*zT;0da|fxZ^rb30f$P12PAQ*YOOzQZD)F{proXv?>*y7EF1!c|N4h3(E+1* zyOlH+HZJLZ{R4XGEw8!Uf4dy><6RtP)$8Q{{XyV2gcM!>egVU<@k?sfaMJ(&cv9&s zg_i+@vN->GF)4$2`}O}imS00lA>#cMK=$h2uNWr)BYp5cj1-LX!oSBU?Sc(S;+6St z(*-~J-@qnkB_{m$NWnNQ{=Gn?R@`mG6bc0YT2lrMCh7J7M*n}06pWMje;DTgUXpn` z!To=~!Up$25-;<=M+(Lnj*Z(+zCKo54VGUh#LptR+4!J9isi%My0J*I)bawh8Mun|$)xl|L5#e99)K0p1#vU#*rh-{MeA2>t=_(@Bmr4u!U7q^ISD_qnOYugR0ZEK zO0G?JhXmeev+A1&F&1mTQL(lDWQzntn>$rtMJDYtP^ce$JgI)?Ckv3am)MYZ@p{Eg z3t>DkE6LOEvimg^J_Bbk&Gv6)b@TicEy$F)0s~Kkp%d-zW&E|50gTe^%)d5f^U}B% z^IF#HEByK+ZvkXk)bI+-8_B{hSVRI9s;KWC9XTKd0W^D}l0#;y6h#a;QXj#+Wh{B zM7YXws8-6zvE|SXt#9lUh~8bl!Kz5-nb+_wMg-xrpb>BfEMb5Bm@RIp zw0(QW0RBj#>(R4mG-pb^M!Pg&)H;=B{JUhDKAzTQHMVt?I`WICh8R{bsilOXZ=Wah z&Fo`^Q+h_&Ldb8YZASHuCfZIp9#vU67ivny@oHouXI+MN&Kh9WL2qI>P>$#da?+ZR z3=w;socs2gKV+WWNzOiZvu&$?8U?>)G{M0%y>2FGzJ#iM{P7iC2o0hluXDD+1;KZ? z>AIuI5nqOmuh*O|AB3Wv2`L8fe{QJz*|;zGc({DJES%(XG&e=JMQ-mvYen0zmk*nY z)zq(OzJWt`Uii@8&Ko8*54_D7gl zgNutp8O*9WONF-jASZ}EIjS>@v9)Bk(hDSKM9J*L@St|BelVi;t=i?DvF~Mx<)*>} zONf1vr&h`F;bvy@cLih!ll8(fCy9z6^6O@q5$N~ZW8ISoNc6hp zA-R;pf=F1k!psK5cYHADxl#_CnpLb;h?-n2seajJxhPoxny0*Hr&G|Yw-6uaQfF1e%DlH+0a?k*`@2 z9<{@5o8`I}W7Q?Ch2U09sT!kSj=#mKZ!=-6rKSP+Bveps8B*CvDL^81`n=6j+(hy3 zBjf=)Fq5L|CrlcQ{_Cnl1EGaz=Q2gcgLk#_OqaP079s3~oIco5tXDT#RA&-u;vnOw1;4Hv>@#c8DpZWrj!i@>t@}Vd>wQvxIRzLl{ILq>P%SaNr9%p zAvtfvq+kfE>L!as+PknSl^AOU4aBlq%CnqDjo)-z^5m-mLMFL9mm`Fs+c|Q*V9zaM zSq8ciAg_#lf3DQ-zRQToGi1H78^Vr$sqXor`nH!WQ?^;k5(BoAY58r)Vj{*hC= zo6f8{yDaSB9%Xdi$x>rHT4KOCTUpbS1nCwu44;rV%SF+@Si~0aKK|a=Q?IQqF_Gpn zD7t!fvRgM{)k=SU+`YP8HMA4|a)jh5rKR!42fKbTeFI}C%YBsE zC#@t%giDwPiDRMYzFX#6O^-@du1}PkYdJ>5L6t5iZ)8FeKl3+ssWK%(Ypq#SO??h^ z_m5i7=bBG;n%vc{OZevE8RVwU2j_M>9yFSlnU7YONmVWQo+K}vA?xOvifAQ@mnV5W zcUzA7o%^^fBgHn^1U!FyWB&BohwL8+S;ztKn7_Yt8%~W9))Af} zNs`O)rI4gTJC@Q}oH_@}aMQrjr@0@L>AWn``nzuS9HkL}{V!YnD z7!t;M%zJjH*t&#}wV)xHKFCU`)VsC`K8WXn(K$}p!b?`I72Ycx?yUkt_o}=q9~~K* z#}`ZshDOh*pExvbts@A%LS7R8*3<}#DQYJ(TE%Zkb| zg}z59)A$0|#u`+x=yO0w>fVy+bji0Ml{gWmL%yAy3iwnD;e+$m`I5+ZTFr&Il28+^ zLLnH~ILWhPizeTYTFXqINm}pkAKlAh=G)Wx+&!)Db;9ubsXrGo$4*whj z7HEe;#hGr-YU;u%q~ghL^Zvtq3}&jEhxQTE-TSiLax`DtdbrtuM$Xui+x4&{R);m) z)b{ZAagK#%EHM3(n+?l?q~ijPe<+a^A1+CEdfGdrImhfQPreRup%r+!#8&y&oxTJ*hiAPc zCWihXiC|Ve4Z-8O&p?6Ay`KDDi|wz6<8rp4b=y7`Y~3e(%S*^U>nbD%E?`thm;7sf z(g`3-cvhq`O>hhnrH;%;!{oU9WQ(sd2sr|8{aym#s*Voq%o+}vo18=1_fhW9ssO(Sh0wDj6zW2jyxT6%n zSu$8y{w8$D7tcbSUP@mFF4-O|&_etOq|6u({F8KtfTa7Eht30++~Z~zB=C2|tIsOf zQnLQ@9&iPQQUJL{g*yrCj#QvD)E#R=MrB_2=dVpaz6A@mPVK4!KVFRjl z5&J+8#h=38j7y()yRL|32zKpxLS5H-D#r+f2b=zGU*iiWFz#()0W3 zQ?a9e1D2f%z#06>Gy7hGSzZKTB=RpiNCw4XSGzpeJoAmb~#SDxk1}n_u-+uUK@&1bD|G1+x4j3=t`!Co2jPh@g_Q&%6 zm%QeIY?gYar1e!<>I@=RH#g6DnUptwO=AGVDoFxX>E+3jt_ZKr3u;HoEYj_HI$v#? zD!q4V)w+SN^0cAjj~H|O3G!}%MC_WvrTcAWzzoj1f)WBb+B^*qUnmxAx)bLa8L$Uk z0KEQ}v3P;2Htemmtgr8>1xCw|em8u%KfCpPSOixK7=O$S7Cgqq0xT+5sb!gxcFM)( zQuosk$C_o8UDC%vfUWd@j&ULiTj-5KEa4qYYUITQ9_aQ$%z<_fk@Oaa^t&l|;0fu7 zG_Dqgin_!U$go%e9_VKw+t+>#^T6%@)ekJ}^%S)nq^&w$3QIklG~&_YHS9g?iG_g5ScK?@GMB zkda+wpy=Va_P~4dPtcn#fK^QH<8JEjPZO=`-mQh(a0oceiU>UE2p*3J<9xqN5PKS{?vl3%*&W7-(dW8yLQ4B%#oDyxxORnNc5 zoa}&G3kz5cGmOgdc*cDh<2}u#nX|-S?l}!DZJC*^O~JM$EH@%`~h$tM!2Syt_Q^-KqaNZRRKZbU)1 zr(o(zify^l)taVV*v#psek=b)x)+a^o~q=8!oPrF)Q&v8av#e-04HsY@Z*=8{xP61 zamRYmN(jdZMECCaCsMdSDA-WVcJaK?0r0}7p^$8=F$;mHdq09bkH5Yd*et0qrP=~H z`5Oa2^x?omal}&x*iT5)P_!bQHFv`|axdc+MQ^ySAK1|Tjt~m_QMsPvPglhIS=IFn zp2fR|sUqrgmQxKC*$A+4Z(MqwAt3Va$UJA{pEJ~_2Usq4(apkKRo9@Nm)IBj0Y7N% z(7e}`U!EeLlgy+paTqtZYj%!GG;nBG>7O)mwC{?%X$v@GnyQ0Qm4X{IENZOk8Fm>y zNQ0^=Q?KOZNbx~duTXesq@yM}-xODdeDNO19r(fBry!0pDrUkiGJ@kNn0Krvh7eee z0tIWTL!-KfzmoX9k2+^7%Dt=I6;3^7ArW7_ zX|4NkWY2y=(l-hVC!OedhKIugLV~#a;K-uRk)t77mj>Q-@da(Dv;xMv2IgaOxk+w{ zji&)FR46+eQQ?O!@kv_+jFynp$@EZ4ahmI>5{B+w1vL6jWhNx$6wrnINAq44Xfw37 zmaH4w{n*v~j&Mki)qO)QnbadaSMU8Do4{ex_QfRIik8|pIrA^~dv0fb z=`>2UhjtX0wfef_E2XJ9_Kc+5u7IJ6N5t;bq>{59)>^eQHwJ~oaCFoAHT&eMYZ{I0 zaTPC&he}V}DH91%dN^xhp~d6JKc@>a)@5^ABC%)&Hb;JtQWWVr}KR`d(^dVfusqe1e66O|J3A8Fbjc*xG32%4*l+9@4CY}j@>hB%n`O|>46UcsbnA(An=~jm zGvh!VR7y>?m)K1J=%dw=G|Gh8R)1bVT?9~jKqD|V_f~_!p`F=q`}@~VO|iFW?B3r$ zssJM+ZGGBAu@Hk7zWN)B4ohQ-&X|#X*J$(k`s2OzM8->%kidwkuCE!2ag zYN01l=LFBsg80ZWDa@Ke%eOQ3?c=eN|3G6@2hR8z^*^ab)QN#2;I|e)n69ViHmgN< zWX&~`=O6KkbVV$>h+X=)>c0HQf0&+P*x()An>N~a>DU{|&)Fax>hxAz^x7?rU|?i2 zUy82!p90rkvrLDmb#SQ-xb}vo^6oi}=(k)kKvc|O%6#MVd=_0vjIu#_7oLS1)IZPm zJl*Ra5Sp=ztyis4G`bxnCC`yA?3gjK)P#vnh%H@xllXcyC6dKcHFmvnbckcaQoOD$ z^+kgoEp8lNOcKdKSB>vKj!7aPrl|OLa8a$w#mD`uY3DX~KKr@maa$qo!Hez6ZaWRJ3CG^-V8CjlPj>bzVB}h-y5D_Vf2p>$yd&fhqT$&hq)go4Epx zp)@JRG+iQ}<5PP{*;K)qVt$|#E-eY5$G+3UCd#FRTC25{30755O*-00mdoz2{nrxa_a zB^ULXt>M-i_@R9DPB5fGuFqLSDblTb%kS{I+QA-mjXYuIHN8jKC$vt_6ff|(u4~ZH z)Jz?6pib^lZuX1A>`COV*r~icuIvccCnN6{55p;7-_HMRWyq}ok8C4j`{F{f&zN4=`ru|JF z!a$4n9ebxw7L? zu8wjXkP8`Pc4{qAQy!OGiv9Lz+75uS+Ou^%ql<*G^|=w~QOeIJr)o{;xWq`TWrmxI z%Ju!vf2LEmE6LSfPpRWFChya;oMF zB=?4meGVt)0FfMi*1%H%SC67J^A44aQfZY~H!YVI4yK(y_=0x-c8QF~W7Q*=(NVjNs$yqm|W=K_xtF1Jn0%KCCt%x^uXYI@hzM)0w zg4kQ++N8iDoOK3JGQKSawxlEK!VzA-qG0ks-m_c3=K^|+Gip7jB0_8z5^8l0S2Me$ zo8T1|L4G|2q1jYK%)+CS$#HwIQh8_ndVCRcc(2B&+_}k&`xMUv0a9kt`%>VWqn8jp<12|~4p&6Ky|r;mn-{#cc+c|Xec>lZgY}*EclRPVbO+JFj-tzxr4votAHtF)yxiwZ+~++lG1-ew#n?gcZw1zGIZq>C zG*-fSoj5FKmugdvyW-i`d^_sWoNOmIfg0rttAD%T#s2UsiS zUveUomo!Jt3Q6_x0uD|_YTnDr@h(zJMuYWtZ4bfO2f@EW`^Y0v-^^!%_&RSEG(BJO z*KG`-f{1wr!7*DK6*qlujA?4HBQ!xWLC)JJTzSnN?$Cs2G}A{Yk8RcL0{ze+Q338R z?8$@o=+kf3mXyHcC6Dn09d<|Jv7S*@N=wt?E24gk1&A7>~IHlT>)OFEo%YK2_SZ(tTK_=}Dm>j&~nWnN@c<-#=IlA`sr#B?RM{^!#ZsICK|DP{p zNf%N}6B)rIXtnPNDOi)7mb>0*^S=89*k0TLDmb1`GP$JE46fL)=el0Fq-IM-_Wqkl zpiRmUFhh+d+Fb%*f5Qg>+uJ0Iq$KmgG%P5EeoAd z+c8M0J%q>$SmG#0T+FW#HeY=l6q0D3tx3Q@+K6RVUo3$W%(GWkD_!H|F==2qedX-i zZK)!6#f_W4(5k?1@!!iR9Pex-ANxj4$Z@{qhJ{kcRCi(CR6fuZj8fKq4Wh}{XZua0 zzqs>ulbFKe_2M&iYaJUL6BCo7c=`JT9oH83S;}=9j)+$F1NV$~oNm+|hOgCYZR_Lv zYjn9#KeBalv@^6!S#2&M3!@xlGI^w(A{{myZo*YNw$#lt%%Bh5KqKUT=<{?cS)ta zV-396K71|j$qHO53_R@4)OEJ%8Ux}s8S$$RR&+y*bWvoV->b~3Eu|)fUm*Ri@N$1D zRpaR>DY%(A)?Zg6JACccqD!$5=H{L|FLVo8!>}LWQ7xQk{F*Z?DlrGH=p7bQV2Ue7 zwRnn{9bO|3<{_lW?6w@O<;#c-jki7L1P{wIw#XWugz#YzAv74`^)aJXWcbAGBpl-S zg#U_k8x8iLnWId!k}SA6Ruy0GejtAa(W{{%IOb;Nf<@iz6i)od*NnY)Wq&Q#v7~9J z4gDUMat4%a-T38xor`Ry3IkXjZ@NsSnXVTPG03ZKS(Sgy@c><axE!PgMV5&Ld{2)X?;Bb~-0cUclC46- zjb}pBPh(9_0DAb822k}XpcHs_ThC!=bT3DRUG0}AL@t{}1u5pAf)2%2YiAq;5>4Eb zlSN%1Q497p6M7H;Rv;b0WLy{fcYTkj4w2l7nL;vObROQFK1}?_=!OcGRP`6MHX{h5saa zy7w{Kk4JTTkE&%u?*}H0QSj>=YdzU*UFc7_+b4AX@gn_pG#0f4v^rVHK4sde`{n>R z1t6G&3x!13o}&s<;XsK9PxD1>D6BN8DP3WC3}l*k0_N?wRX_od`Yyq+_a5L9Ae-Yw zwcIRPm}DmCsq!G({k>hk^QI=^iIV~;bdRyeoLg=9Rz>Ulxo3O4y3#*7H96?X9E@X8tG!&T-4%V4xyby8eX&VTWy>s!&C`sIF* zY;9h;bLR}GFJ|&wVusqyPM4@w6{S#`a{)?CnHFU-g|;7o(#S`A|GRMO&xoHuj<>M< z7Kro4SP^$=etdmHFH}+igGMd%t!H@cgdEoAJ<)QkeOMwidE#?p&%VHPAqoUXf(b|Z z-#A1J6TU)9hI}i}+ezZha16YkUmf`bRw|xXb4E8I-@NIrnCm|3GgH)f%Y8Q=bhp%* z`J|bj4@T>l4EV0;vt#hP>ak)s3!`1KOp%8>ME7I(jax>3*v3liRNhcSNCM&t!AV&b zoiojIc$UK+3s~J$ppzQfDdB1i>hWAlw>)p(5<)-InH*W$S*|XLR+>HT;(JDqOZr)# zA!5G{S!GnUe=zO+#r#b&;Crhb-aHgtxw^lfdEVT;o73|gorA2>$V5ZOwFGeIC|l^N zQMB4I#yvm4I>1?_W`9wrU|(A|4yDnWttl-0-@cbQ`t;e=e+_CuskSpOIL#H;3U>LF zh#mW&a5}hrv@@0aF~^B_==(K$aGXHrSCj=S*g>)u^$$~ikZa6$4AE>-KYmE^_9j&H1 z!o?0wPk|b`apvb2i>Tym**EZSQ80pWR@G|O@Xd+b`^wj?;q|AJre5~@K%P6zS=G-! zC*Wb+gb`+*Q~~TdYV0~9znWwbX}w7<3=44*1@Z)bst3!b5x(xWAMGWU>d((kW;*0r zxKIW_LVgi$Qhg;}k|Z}XYGTj+2M2)Nm5LtKc}QfXjbq{6vVMdv&rpsiS?`lnQlv$eihF{$)8Vi zh4}<$9*S)+pU}3@*@rl!Sm($a)(i%p>7Q4VmTm@nSr}IkqvLh8>kmc3As?H;>a2#D zo#xnYaW`#`=3cIwbq-5^mXr4xL@PLYN_&7kgw+9dGPet-IgOG;6`mXe+9p}{ifEp= z`Bk7NZcQs*P%a&xF>Z?E)D+K6wbd^Pytdp`7hI{BP5^pqfL~AfxZ9HH_*ClOGEl-K zK=t}7hT%qpVbHCI)(LZ%ERKSey>EcI2+diVZXWY(U-$B;MVfMN$z_zc@%zX3`^<9! zsv&LFjg$4SX4f36UZwkQsaN?J`CJhe6N)&l?YQ&xN_`x!6~L6#)wpGYOU=yYF$`GQ zyD6Pm#B+jCX8>wBosgk9o{j4dB}(o03qXKy52-L?udKrf(mA1q5j!V6M8(EeRNp&? z(o}oHT{+>7l*$}u8gzWMF17N@^)gbg-Ih9^mFH=xYoO3EJ9s=iP(_#c6Y%g}EW8I) zkIJ6qOtIK1H_$1f`pnLr0OnGl$+0Cssmc-)=q4hdv&XAWgBllc2$(5=bGl{DL4CeY zTV~o*v?+6sd&R$(Y!xiYHEoxxIvf;TqiuRnCpmM&hjNltb;&!jVMxDVY?Ex*P@biE zB42MRMFDj$Cf3dv(&BMrS#nEA%hwTmNe`hJE$^+Aq~q0}2X6xSsQ7Z;`$il9*k*kN z8~rD!eAV_QtF}PV&Ypy$1zT~fa&DP3A}Ho8rEvOs%6)RnF(c>d)gDYNwOy4@Tds+k ze~_zarqgwi-urQZkFZy26om{BUiDtcd`Yr<$s1OD(?KD0Q=8`Q>vt3R-FFUO6q?>%u+m=8(QE0p z1Y|b(;L(wF_=&fXsy#V_!vx($gO0=irJ8Ql;+DQASov`2OC=ltqjw?{t6Gn(v$e`Z za}K2hjXLZbsp$nEs$+O32SL{*ZsgXeV^aC1`mB6&KjgIKWeT=WL6@rpgy(&ZOvJ<9 zxsNRs6&qb1Y3l|Faq-ivQNQq^9mC6pRyjypN5_Q@OuCqpg&!_ zIM*a^nN&CrtQ*#Ss{yV_NJ(vV0;-hPn@l1ej@9q22m&qqIqs;49}RGiXq^_6M9N#Y zOqIj=tYy=q@~O*P`yWOu&F$OeY(+ZJ-nzK%b8h zq$L7(5v9Cj?FLe?w~-pwckq@XTOpu6JbYc`d6r3s&Q^p~8Hv3zEryA7$NmCR>SWDa z1-FGl$&>A>)#|Z_RTWvKKFyH*0pYr+b+(^bsg`wm!IYx9{7=CVqGlFS)JP(>&Tvu+ zgFvk!NF`h<)C6RGL37TGyl$@9rGsaW0qKs+7ey(X&As0$yNeMIH&Qw1Qtw1aj$~~q z7^7SE2gMOMHOeTfkB{mmU@VGmn{J<=)eqd*$#S1Y=l3_YE=}4do@o{HTom7_&z-BA zrWA&~qiq(v0c5ElU<;wP^=>VLg`WQ;w1O&Y>@vvy8f3K1MkD*#bF2YyOCyvmueyl&S3jTLC#rIaDxZ zC5G8N=d38roeCP^ekn1>;>;)jzw!G(rmgI5Q8RSd~Z_)i=P=v zXqQjT(gFE#%ly?`Y6|6Fg*~B%Aw(=>vrv}C=*d*`9KaOX*1nmf8p&6DjzQ^D$|L#0 zed|FJEcb658Y__l_)K-{eEUAoX&gc2iiFH_@}m2n<|#TJBt>sV_-ZY{?5 zfy)UoHGhW{_V{{!s|IYZiw4OP)97ge(zfmJs{F?X#b{VE5B=)&2R(xG7PJ4@?MUH(?>udb+}6KjK7AH)0zxpOKp^(AYh8eq^u0 z1cM!hAOkqsUX;6UR|Qub5mFpcy@3oR6SD5yGI>USOIJB*y<)*oI<~A4$GS@-jHGR| zH?hL9qt2Tzx065wdvL)fDzJJvb+zSw&B{hP#RHfAJc*33;26jkpPzkZwYs)?`-!lF zcehf$K1;{M%aFuuhuOjpw^apA&Vd?)4@kjFOqgUsxNA2rt@8vK^2kQ{u4ht`*n9LX zU3foN``j2nXJH?0WjO{O@V4f>u%g=$$Ij>as@ug{97nMdOht*;tEq~Zm9VqPHX(E9Xc-P7CNiE?=K z$(s~COasv*mpWBsqM7gX>B+*mgW>LI zoi&n_FxEX+GjiG0KkT8}m{r`PCL0W(V^EEV4Wy!ah!Be3w6&~ zJFi4^C7wu~TNou!I!jFpXo=mfnU5Bdxb$T+LTUi^Y15--!T!*yhOTw8(e2p`9Nla) zIi$?0dIl2wl&T@g8E%pF+6v#p5@cV4k&=m&)Q`_hUeCVS&?B4(FSQ_K9IJ+379WWT z*DYY``c#pwK--n9!?pcRcV^DL_fA0)Sd=x1r5x3-ad)&E{qpNHtg!jY!m`xD5{vAA zH{Ds$EFCaKe9U-?#ZCxfPdQ1AJs=+xbWXW*kvLTLWu^mLkPJ41X&V*(GsF1KT{Hy) z>=&U=s{e9dxLil{NQK;N=e(ENV!>zt{q0$zB<0=3Y;6vpGQ;GQjPwyv2BT2SE_)RnJOIh!TVcQs)$W!h zk$CDlV(=t{WqX+ig;Vr2bSA_5htkO;VIt!x5G_49%1!^M>809&eGFPA-EJ!#*t9a! z5XLeauFMMW;Bmv7Kzi_ed3}7 zGe4VT)waoeG2H$EYV@?FfW!Nyuz_(DSRc*r$aybE0UwmBxP|Ok+=2RTy+^8PSdrp0 zOeRwW?CBu54)VY%A!Jh0z->a;{)arZ5DR{aJzRY&Vf`>?L`|v{^f%jmkc*mTGuPUU zkW3kI{<)F}GBk2A+wz8d(Su>x0nnQ_ncIw!T>e5bi>w=pH(tXpOQ*keU=2~>tkH&% zOF2Pusj~R!p!{hT@1=Qm>$0s*M)uf;gIbtq7b@Eq%<0BQZ{E>huopIsl)0{nz zXVIFlzkL*Y9#WQ(bPSql&0Ad*7GiR5Gx#2VqK6l7%&wj#odaV+J`&cDnu;Yt(QOC` ze_aGpLOviX+SCj>dmW$@x*++X{&C|S8PFk?kzSIdN+pR+ppZB_ z^<6ePPE-eX<5 z=TRTl_h{7)D-!Dqxfph&trK`PeGG9`rlsqS?GBt6CpO4s4LS8Lm>9@PNaf>MPo}_p^ z!yXu|v_Q&S`x(4oB$3RI310QAY>8$QZN`!Kp`(r%@eRy>*Y5~?dgGJg*j>8A>E#6R zVUI^#7qj;T8l!oYB$rw;0Tg_xx2~Hb>lhva%kDCHf3V(veztoKS9GZkE-@|9Y1+j! zzxl1s^XK9Q(oK(Kjdl*$8w!{sYNl!{EJstFMjs@t58Q)xfL6J1xfx;GNzN1aSF2m{ zhs9;^p_<)(fuU{RpneGz$~yXCfDtLmHt-NX4G{d(b;TILU}@O9f;$IKgXlhuq`J;}C=Kv4nvYHs z97&qz>_xzmyI5G_LbN~JpB9nW4QVlSQ+L`V*u8fmQiH0`~K$l?$LecWmHz~zBFLRA0#jp+lTgxUV?VDL{ zM-*0b=g!sFa5o&%)liAFH1=~X6??#LPls+Rmbh>3%L<1;VS*_yBj}F6JwS5OLK5?Z!>r-(jB=c3PT*cu^=T-%2HmdK;`hz!4Ep~=H<4n+VhYu zhK~2f6R$}qly~>k1jg}(M4l8coaqS4!62_^}S*_{TEWF3I>7OxbJo7J3YXyu-+0Px1))}-S z_nfdzS0#j7u?{5Ch=Mw57!dy>qnzL}YDsbf#V^kFG2*89B+T0O^IOKb0gMo?AACK+o?Jm-b9TUMR_vfYTknznE0L5h zO5`)uM~8ec>!au&q=m)Ox`So|#3QO7-_ZMh2~v)-wq^8Hd!ru1J7U>-R=Aem9?QES z`eUqFnC(Yeac@1(D6hkubtLr?rG87=$ukU*xk5`6SSVHDyfrlQnN z#Ir4F>^Pjl|11=}^$z~F`U-mDz8S7J+&jENU9uVvI}@+?`I(JS9s~wN>(fZS=k{x9 zE|Hj?2!t3E$a&2@2vP=k8#aqewuvPNt~M`)a%}TqYN#!Uy0S~lF!X%l(Ss$u`7fQ; zo|Jnm=H!YQKBdx>7f9jTfaw;dKgmvgGDm9*d6Vz3l{s&`QcGp};-mLon3>?;Uk1Q6 zips~xCWY?g)WpW|j;Pf@;^n41Mh?DX>MD|NHiZWI#lF3j-QF6Hoy>Mi1@)YU?Te=E zH@w3g+qvJ1<9xiN^YwIMyA4w#!f=-oKn|7sLhAG@$pEOTOmTq5b>EQr2iblYy>cw8 z8b3#Q{Vl@SOPSYnuOD5zqW-Cztj6&?wI<}%_&A5W6%cD&B^dwj*z6xB8SWRCbQ}XskK6E z|6yG3b8m-hQJ}XZ1w++IP>P4szi8B*MR!KfdTEBJp>4g<+IXSc~0ti3ZQFc ztPbfkC}SCn2`ssENZ1-tUKp<8*83m|7*+$+S4!6jf!){mmp??U*XuXmrFjg5TI@&Q zTO(cwA@E@r0eiS$)#HyiO>ax{BeqseQz!Y9w1BivIb+rJlD`aI?~k9e1WHO#VCM^V zI0D?lQ3c7bcj9-;=3}&tNPvp=jU^;L(P!2Yf7$b6$G|?8+n45F)$mVQ0j@77FYq$A z=AaDY>wiv?9HDyFQys1@=SE4wjX^`noPhiRWh&-t6EyY`M7u&t>?u7X}OcXHMH(`Y@(hNoshFl_0Oh_Zug)cKUg~~G&MC%cc`?KjfsWc3-pd~jAk8=kT$^Wg`W8WFs)Ew;E0^wda@|_TK(Rh z+({R$58ak#M!jv4Rf72}+9%A*U^%shiQ9n4Qd`oguWKSv3sd{2Fv~G|<^GfpOJx`_ zDqP9#RH7`UES1H-iM2OCknn`;^L>!&U;Kts!T>wmbGq|f!(HR9(-u|*?i&au@Ujpz z^QiSd!9tDJvDfAPy1V$^q}T?{9zrh4f{aZMNJt)?m)hP2710lL7M=-1F9x;6&l^8r zWEiK*kKi`|9rv!2P4iO;d0p{AuAJ=cseJMU8_~J$jrywh z`_5V4S?8>?)_GTJwXC(Dz3<_$?8G$FP68KpLgv@9cTC=lq67o}T!gCW?{L z1bn_4dWacoHD}UKpp@%q#y>eM;wwN*8*-M!JYqb($T^bkK8C{g?becwlN%eo><6t( z(PE47<33<+4MFOX4MO&wl){%d{7_$~5h+DNF&@<`4mw>=eaoQ%xerf8Q6)TUZzXjV z8+S5FhQ#rGB+6|Mry4rYjSv2ciGUDKD~>7DNyM8w99smHCy(ZAk0?#lA5NT{T6a`= zFfYyT2xY@rbe438gp6j(?@b?H({Avqj2%48KT(gWz4sf#EF0^5U=$!CVXHe|wdeR> z%&}tUyL+p88^3OFZ`n)g3gvyWMeinbwP^8BhmKD%XU-R8+6{j>N;zc@s>fF2eU&Er zeO&ue z$1gW?1T@T$w2ByH`KWaok8X#-x$60r8mP69^3CE|WRhO|azS5YtKiQ!Qt{-m+D1eF ziPT)eqC4fWKl`MpL>`Kt4utP{=(_&smwuhgCxdDfO&!J6_>3WtXteXLLlP-%%W?Y^nBAN*{;PXm&JiT>Yai{E{pg5vCl-x@RY2T?qarvC<5l%pWVw z$9j-9SJCmqhSe0-hzk>_Y&^c;RWMtj;JjRL(j^#z1$AX3AQ+pxcfSD-BSrrZjboto+l@jPIPfD&_l3;S1y^<&jWj zcGsTp6voq*CTIL9m6KH7B7Y$Y?q^yAabi7AB<=Vn)um%n#iaW=&i`_+9fQA>e;!#b z|4jFA$ljC2aN3eEFgV{_)A5X-Dtk3Y*5W}*cUS15snRJ> z;SG%6`7qv`11G-r*X|uhEK6e_y9u*)dJVIk)uPWSt%qtfR7+A;0p3TB@hS2CK+bNX zCM_fSiLLs7%A6AKo%0}n(->sI7O*~gF}5iBKcg|Lt^oJOHqwG3yG)0vg8uraYB zW5xJliIK-Ns}!)i4~e1yig5YgX7O9Fiq}Dtj|esLWRuZQtQb;Nh@ARXh)oAE=Y|2$8H?)L;_V#42`uPmV=FKK^qh9= z;==r&?KjoD5s>5EUj-ah)$`+YORk6WhM@GCOI~h zD=Oa%Bs}iQBld3x-MpaqCzhJ>)^`W;CnCl=&GHu6LB`@5V#>zcoz5LPy^;Q97FesP1v3ovrg;x3Yy>phedHRb}fP_>+~nF z&p1>%4et;`+IgBsa16n zWk=!AhuAuAimOA>1s{h4@c`&zi=V}s3|htTU)1o4ZGA$VWn}I4x$B!B>D+VjIDS1a zDL^HJm=wUuV7l$WpVyTE2Zjd-advRi83>@Jp!yDOp3L}zkoc1_2L;6OCeY@AP(~@v zQ_n>m$0#J3d0|F-X zpjMWqhlTkYF443)=})cG@Fnof2nxCT!E$jv5N zbXGqlqA4P_(|z~!%P6*uhqDB4i+NqyXSrU|tO-z)pUpa~;`?o4uj%C%W-3(f;;NU< zJD8mvFYUar@No0uQ7D3uL8s`>8N2%ymqhJtOLEqB6W;eH`p|?psWuQh9_;w2vbW^7 z05_WbiP^pT#ppeOGV-RY$xTr^+*RYAy28n#MXkb(m{a|n`+KY0aMbl|p;4Rb#hr_H z#?d(6Gi;$!UDQ45qQ~}In+}-n3FVdOVVrpI$ z5a;ZtmX#*GMU;i9fFD&~uWNix{aIuu?U50c@k~t%sC&J0+v!DK+I@o*X`IWcEcN{k zJV5QVn9qEe(d;eNyiu5v)_E7mo_LHjF>C1d0#d=@|R+7#YZDB{e5pKl*r2-h+MCYw>6U?sDS}!R`dP$UILjlqWqU z7G)7!t!C`4*56oo9J$GM?$gMi#}oV!!vML4=W?+6vO6>7mFyu-|JQP&;H>f&`1UyS zL=)K)(^AQ!O}+aZ^Wy-$ra=`#6teB94zT&U@VR{CE{HGqO7&ATd<;)A(_Y;M8>YzC z69EzDDJq_5Gw2$s>4svwTkAnfbf$O9Nhs-E(Gp#_QSrpHq&>vOVifAxRNfvnOhFQ} zkwQzu(YG~O>LE5!>LaJas~ggk%Fm2(+{M{KsYICrL>7(yh*4Y3ecJz()4c_mjdXT3 zim`v_XeXA?f0 zEq@z-Gltpw_&!-|Twjyl6P0!q`(B%Hd|BxGrU-T+X^YIq`AQ_4WV~OgHPmGju-O-- zy?}UF*K_~8EYDGB_ywJTrzWPRTtJmY12w#a7|ASxhQlZgyKzkzPh!8yJr}q=bW)%a z^wqVCTJs%_TH1g=++C)GOsb@O&{L)?b=E7_rocgn^Jtgd&J zW|fUOrt4TPr1aB6Zv0T$gQ;TzEuH7X)5>&3D-iUCJt`N zD2*~J7Y#Kln|E2X896Wv+GBrRSSdbXbPi~a7Vn|{@iKzWrHsw21b^{}`2a*s<&n6% zxhv%57go?72(XkO^z&1MxZ$k@pA<^B*7f|M%y0ILAVL&kGJ7ykwy7Jo`z}a4qoVIO zrSF>s03LHb`rY{0W5tKU`lyfoKo@|b`g2#!KueOrPUZMisd?(F8EM2XVwc^q7%~wu z;BRm-AfxWc2UkO+dH>g!f)fYt5wz5yr>sv6q4~?5twGRy4QgK42q7HTvmk;93{||6!4E%F{gt6&lZ*ECtxauh z#$zmWok|{ys-Vq=UPBD9!XXm*I>eczdMF35x<}e`6167@+vD*oT1oVtg4I?Jlo>V7 z<-jw?-t)HYk_ebfGU!$e@HhV1{<@7j7r3aDla=g|I74 zK8{Kd0Pls#8+k8$rU5c(mk#f?1_q+LZ@ZcGnqtTvCPPtE62wfiJ5*(D>ZAuRpDAe0 z68mRD0gb{JcSmnMuLDZMnJ<= zEnGCLco3W8?znIVV{u5=Ca5PTD~fsoN@S2iBtc%FQSxxfQmbV&$F>NPd+D)1=+`J%^f*5n%k5Nlu3)G7RlOFurk^}pmYM?shr3(_KmD0C` zj5^p9YPnT9qp-}-==SKBv;nEKwQfHEQevOQiliVWCxB3SY{(zq4M2o)J1|lbc0$2- z-M;llT8&I(wF&@8JOxoHj}IQhS1%<4o%02e-xg#yx1PoF5MJH~KTDNx|E0{S6Jbsp zmF)yDs(^@@-@wrsh@FF8v?yLxr>TN7>bUU^JTt~5LmOPF^1f?QYQZe>xv4H;2l4oM z&_392&fN(I*!o7v3>lwQtJpixI|9zm6z8nnJ)9kj^bB>VGS+%`z1-}J^u^=jcRyRs z-G*+Rlc4(AV2RGP@iWV(u18K*dI#T=rAXCQJ^O@VgCp{iTMF~ zqIuF4|1t7w1(a)mc`(Ls1KtS_k8unWlAHk9nYtA>V~S4=RKtVA~?>bKRHODThgGP<$238cbjB z(MXv|2YK&>M@Qo&Csg!FbA~x&y0hXfzBHXMT&I*M>b0Wr@N6*%3V*yM8nORfWTUWr zCn3agGbns(I+=4scZ|M|AFMA}#+^^E3a%wtW0_c=8o{+WRqLX#=9tt=4n^?;d?fQ^ zy=J}tvp^`j0`KvDo9S%%qgHl8=@k zCeg((=+ygpEJ#4R3iPw4XP8-+aB@fj90*iZ!Bn#shLlfrX~=uWaC|cMbW2fe)GF)K zL(oV=kI^#I&g$9?6}pfmd>s1x0oXp9&dp&lqhzWWE+|T;DDk=`Ve-= z_Vo27`lG*8Ya1^$M1Ll(dQd)p2hI_LNc;3U)WvFc=;Il-kci|xKC(-$8Z_d<2@6bi zM;ir^!&kljz5N9$lKB|9MG5u$8^A6M8sqB;^`D1PxZ*W5kT7>+y!LW8_@aYhE|lZ) zr~@#x|`UtgHx17tpup&XuR+0d3aO2{g|8}yH@zzGBgClKA{jIB%N`~53?Jwfn1 zmwJE|`1vc?Y7tmhs{78D{lnF$71$!a8U4RApny>tIDcC+eR%)Awt!6wopvd0V*qO_ zjyNwF;6BsvoZYqg90WjEGqpD_6G!=U0SG(UnzM~241u9iRpbSt!{HK(#5{02|Nf1? z=i`6GK9+2rV)#qep9@>Q@*3v)y(^ZxvUCDSu$em0d%JN{9=~Al|uUz_VBgohR ztL)J$!xhl^_r>N3@ARm7QQai@)1CpZ6#^(T&UvOa;(Mo-|GEsZ=m|M#Ii_#FztYEV zOXlAhPT!WMT;0v)x{zqt_DP>%W#iFvhY7#Vdu%Sa+7Cu9%?6ZQSdZU8co41`hbL*j zj!qE$IzaSgvl7Jj@$H7^e->0QAt`${> zQS*-)g<;QvQ#w_gBfLB@z)haNff&@_#sEeog9IN-@E*OrLh!9*0t)nB5!4PIT)t62 zvHom|@Xydm;J#oVK~BU}x!Ucwi+gBE)V6rvo_H zp&+=FU_982LpmUYJPXyvRyHDCL8zN8{EABA@f|?CF z3AB~}8!zMfUoePYmVqjya3|1F>X&8k?ImKrEQ3b4FFsK$4$F4;{hQzC`}^8l`l|;V zb9TysY2|sovQ)p@$864@F!J#IFl}lF^DC;--{&$8GosLac^*wb0yyaPAtrffW z#|FXbxqkZeFc)Sm7zOj{|360YpYIam=Xi5dV8WaUvbfp^L%vV#rVn;D4B1uv)*I$5 zMAabBkR^!mar{_$aoSa2JP{|u@@hQ_b%Fb(D~V^oB+(1b-eUcnnVwy@BQ4X?Q7`sw zhD?Ds(`jC3`1fe`IG*_1;Mzg`mMPKk#9<#d0}O_K9ZD!br2{1#{e#tf%YOcH`}e`l zD7H6k*Dv7p>XUF!ErWv}FK;2=zlmK7)*PmntMiMM0a!dRwBy|s=bsIePcIM-J6l@w z*uR_p@?TYObR)TY;+Nm;_7C6udpMYXad!f~uD)Ts?%D~~$ar9XuEOopQ7_ng^xS^{ DZ)3+^ literal 0 HcmV?d00001 diff --git a/kortex_examples/img/services_sim.png b/kortex_examples/img/services_sim.png new file mode 100644 index 0000000000000000000000000000000000000000..75eda69b23ce06d04eb3e88beaa712ffd4c80d93 GIT binary patch literal 33723 zcmeEuWn7hCw=LjSN@}B|ba#Vvm!N27e-2+}18BHbwkfrNyFrKlkD6bT8UjD&<7i*^V6 zOLfuA1xK^=GhKguLN!e_g$RT)D3IQaMDqO9WAH%$%h_ zwNJG5w0HKBWw`Ko!wS|TjFx`!VuUL#boqDF$zc`1kp(`n?F5pj#WP$Vl(h1d`8^&~ zKKb4FzNt~%2OBl{LuuoQlTCh8tJCKAquwMAL;Hu6NXTdsNGQ1eNRWT~qcucRiqn|? zzy1d$Qb05WS2-E)KRs~sETs%mTQC#yfA>Q0$gThGk!&txZslaE|L(v3|J%Tx{6AQ? z0)l`ynmSCi9UuT=#`qPpU_z#|mX92xdAv62j19QTWc&y5vT|u5r{5R6Xnvl^%?iew zl7AyW!DYk-n-z|a$r>O*4|y%Z+S$C$@RKL{S!6Gk^*2)W)v<8M>4Sa2C8v99X>Vbq zV)EY6uYIGJ22utFpLl}F{G#+XdX4JR9V|hL{ty;~=}G#Q=iWbImq-8UQsYBMgcEK7 zo&={cw?y_2NPTva$ftVLzX2sNgYM`z=KA9a0Vq8={O{n-FU!2mhJ!#Emwon3|}=~^!_e47Lu7bHgBt7PTFo;FcQ zhbAw_h<|qoGtuGjbLqljhWeo|xXZ8>@&4obiMJ zq(DXDoL4xwmQRq{-U-s^NPMzEvBID~nRClBd%Hq4*XUBzYxe!4$8mFu&qZp5$>&tq za`)JM<)z~kOy^2mKAQR!`%V%kyrEI@|0}SNzv(- z2&;27o+xgq2(6B&h}&rz`nZfVx$P<({Md}(Xt5N#JbX5iE00svc864^)@w0@urG|l z*Rpor*XzPpwCzVp-FNP?kH5n0MhaRrwPECcqoXZY5GlYK%=m*``aTpT4w94j<1U%d zsB#K-S6_zk1O~Z~Tog%-)a6~ai~8ef8=K3<7Uu!8Bz;YMtaQqyU`SmtZK2ATdJ3m; z;P$iaLy6++CLI<}{p&;@&-p1rhL2E4!cVBdIJbEp5z9t>$Jubva}MEXU5s4PTs#^% zqD!*kvz!AQ!5_FbMcqSGP3q5c;|lJXRRu%$-2&sMUsV`jvVV=kB6+TqkvN7%A%)ML2zK?Q^7XdVt|aPC z@0T^Kl3ZLHVa1O;5$@OXSb0NsZewbb-XKl-PsD?qZ4CuWXFj`6f|4kq#R;3D^i*)e z>D{TxcBE>P2$bKGRQF+W%C(s&)l?mlt_!}^%svbX4TF6aR6hSnhIJRI*~?LUwWZ)^ zR|OoRdcv)9Hj=P{ObY1TA0ut36nY1PXZd$=;4J5@SBXe?1fENijBh1t6+WsOLU|7B zijbE($)~7mNuEb`%J~Hb!Vk9R+~&6_XA7ETB0?|;r=4=Too9oJN9(4Q>ec4$`xsl( zjdE;b4+h2OAGj|BtS0K(bIFr?yc3;3x3ed=ByTvQpYL!|TKoAs&7oy#t7*4|pLC@i zlY`fx<;)zljdn5%zb&29ZA{~NO1z4g;1eRtTmN2@lt7h&BL!gKqhZkRNQyHiqV+d! zmfBFf?nuGtDU8L4vVJYOPj%|4%BhwGCFeEY8vNs2(c6^@hdK#+%hTOV-$<%Q%zT5ZsL~bg z4R8)O7<17wCf6Ud@2jsyCaN=K9(AkF|I*KijPOdhJ`xjxD)V0TrSSA;O9ol@cY2o8 zjB|4|AHF{O5w8+yJ7rx|qB*%D=d?L2Pf>GV1m;+?#b+4kwD;kCCb#fTeeV4PUIDSI zQ9_n6pHZEOqeb`~aoE~lVx{4~ABX~p4nc5EE)1ABNZ zzWxt+EzY?4b9|AUjaLuVsFUG~-sAI%!5N-Dvgn*g)~S%&@r=VA70xhM>J;w4_TIDv zvm7m)0snkG7$5gg5 z3S3z7VkxxCjHducRIBMlv6?pa(Qnl|p#zxaQTIeUI?vXEIn6K?Szju>)niL#jHB=4 zXKVYBVv$)PJjr;=tZBQ}Cb{|Di;Ap^*|k3Y8C#P9kppF2FFJSI`o+*%oT)P3y6>Kw zpWzDE8&R83n!C|(D>6h3qo;1uk8{D`{81%;x z@1JC;y>)a^Qg4;Y38~^xoZJ{YaMUJ)aVzKi?v>(1Cya0jRI3kFRF6tvRFm#Il%Jw| zL0ruBEJo?xOf@7v$}q8r<`-1V3aFH2dTI7defET*VIT?vh#Xb2GtI8>s<3V zB$0xti2l@*Mx0lpvWHV`9$Ksypqq3%wbdm2 z>1Z3+GDe`v-#ymIdiBEa<*G0G@#G&E8#aNAzg62INhNzACA?HHS36^GGo$a=cDv?9 zg}tuv(R*8xt}ivuW-{EqPwg-|Umi`QjXgJPZqIVp3;P#*S3tlTbhc@!Y*R>1XTaWg zyZw6-wlMVCiCdPA9!jEb+t@CKf*NLC3rxP3A*wSg4{t71Y1UMEfNt+W%C0`mC}MvW zCj*Vzt=-k|`}MfY#_DNiAiUQdrhEKo)=>&>LQAns;G>~ihaY=IRx?)7iFdYB%j}w? z`mn_cou0zyFs{Tf$K>kw*=i@gN_EYn<9R>7s{L-#w2R%=d2>7_CDUHEy6WxO#7>*y zico#m18{g}8s25Rbbi<-lfv>o%eT?vXzY1^Y158%f=fGGFm5{ zzY#R)-ZrJG6iR8LtYeXW!_P`iJ=XvOr@MwtS3m0O^v~JmITxpYZ#e5*ij#@g=h5D)Q|AZp(|P5-!@A*1bk@-`fU^Z z7i$MyKDJ*fj$%})w|eRa#^Cz|9)B4x&)D(dLNm{z{VCi-F}1jb-a>KI2)SqW#u6S? zd-X=u=@T+)@z6GiSQ`WHec6L?U5Au@f%(}7u9L>&^98V-#!YsXz>?Z&>)J0xm5;~u zochhzJt+P?K*<2e<)orieTmX@cWBW%Dq&WCHb{aFUF7O?`ORUI^^@J|ktZ5X#C}w& zS}3!I_xX8=?gXfVeEu#xet=R{1jVd5n}wx)tld&hziGL??~S?Lh_|6OS&#E8CrF)8 z^hhQ@E*jJ^%c&qC4XNF&VL8Ih7msoC@{OU|Cml3X6%a;V-H}KEdguv9fjideodKj4 zGqVpbY3-Ib+ByYeP~Un|P>Ev$eoFbC7m ziJ4TYXaJ~V;@ye#m&k{lrdxyyoD9GncBnofp%qK`57Nb>po{@}@DzYy@o>`d+^eC;N-rB=88f@Xg=MZtMWHyhv-m#TKjn0k~~Ao zTNHyJUo#XbtG6eZM4kl!c9-yxPI^`RF+I;rBExVOoD6mZCA@pd3_l*kBV{RxFNcod zDm((SW#XEa{=@^uDT+z7DwTa3#d|>4e|4Ctb0XKs*xC$juc27E09L&OKF=(M?AZDn zK~TiI-O&Q5{RWcQ^{o**UG=MnCC#pGF43q)BKym}T^rex00}1WEUPRL3zQ$z~LKaJsjln&Zq$C67?Wf~ALbQ8{NQ8&&p?5kcV@U#X zd^X@jEWP1FFlkcOr+Cx3);~7lmGU+C&u~~zitt6#c zjpV0HRaw+IO+Jays6KU_rV{d(Ku3&U5*LPy!UZ<8(_aQ3?Nk|ze{i_N6|Iv-_1)kZ zmcXo0wAi^NkNcjH6CyR$jO!Ey;R8BTHf53J(?_3X`-0qSiwlto+}y>PG5>}2C;lM> zfv`1uP;~O$cE6j06tFwA^Dh1g_n`Q-_d6q~TckUlVx30ZQd+6S;T>c@L^uezYGDV^ zBEn%PhYcb^3&Noz+n5^yg))9y^IrHAAlDvJ`EY~HN6q}}Vi<)zIDDv^9|nfGOuyjr zIIpXEW%i;7ZdZ?Neal?H8+hVz{_}l5Izze&Z;z!5l3 zt{WY9F9Hmsbt$9<*D^#RPHe5x>~wF@{M$Rl3Vm20d?Rz~)uhz4E z2cg5UGDGp3G(6{4-MM;ou`2+eW2)fEtdq_5Kg2S(k(DlhLN5lodtmV8= zyWB`}`vE$Yu5CrgeI@leTK8Gsi*56zPPqBmua%l4I^Ti;xJ&}5hyxhR)=oW4@13<0 zbMf^;6~BQcNO*}@0<(#AY?SYaC9qrPe1HN6p-I~=Yl3zv4?@$AtK$V4Egd2>SJNEq z&rfz8d@nZ*Kf89AB}0;W3b4bynhoTiaGuTW`dTEdDIoovt||ICUXpfs@s%NKtDIED zJ)PF1)0I9b6m0sPonbo2M_RDyz2(Nd5GbJGijk4{lnaE&?CZW=m^M^H7y;Bi17OKi zs+@m5WzifJR!`TkBN-zY9`Dd~Xs&6v*lFqqOFNI-3;2vx?UXsG6NrH6;(KJf9}l9n z{VtD4G3XV$E$P^;GM>FV&0oR4l=$R^;?3?8LwPJsNe&>Pd%ERqWCxHPPxzgQumdI` z;fI2)fCcu&$&*_})PDCq=#LY#>|G@0G1pR)6<(1sOa6F$bzz?2GH#`VgCO^Ee2;k( zyPZG(_!__cGJV1R;Ua7)8c!IPn2+_TH_yvBd#VL8kW{{h+zp}{f`U&bmcyWs-&EjW zWoa2RL3HR;s|OouPn!YE?q46y?dSUZ;Mt7WDaG|^Si?qPkgOkD_&iS;HX{xIb<`<><&;u?LrYoYa{GNU|`qNk|wi=)Lec& z?jalDpyNA?1MxQ)< z*N$oaMnjX!BEv*{3e0C!w*BVj+fKyJ*J+#vMNg6ufVQ}z zo5cJxnOpS~J=7@YT(xaV%;!8gihufxd9H$yHXu2DYVu@b#*qj$MjBhNvxUGdGO~T5 zdM2m4?!zMQUm)ua3S8#_(hIRaBlAbycsYo?q`PyvM0WEp_mY6_12YLS`@3pd5cllp zkgqdxof9)d#t(0P=Kty)Pw6;c{!p07awV{ucDn#c9{L?ed%Wg-$zM=XqCWOZ zbHcG{mgJ5Rjgw}fZd6l0>+^l(z_lExaWf-TUr_m0Vz|hq zkWk3+zC7jpdP|xZg5M<*sFIq46R1dDH9XISr~EsLEKwT4UHs?4*8PsA7zcl&qZ!f$ zkP}x$WIs4Br!TrbtdbFkT(*D&@r+bisCenjw&V=BERW+W2m082eNtyXw~;#irM6VR zX}tgUE1T9kt|l@^0zk*J(M>=UD362Hlsu)R=@rFa_uFW9`rc(AARNx$C^-X_;%k_2 zE*L59E83xOqb2fn4IGp8p|>@@HNmFGTT^^o)V~+X!pecXbpB8aqKfpYHmA6lJFG< z**UEZlpGQAh027Z?BHckx5G_#^zQ@-__C9)Yvsy?zrV* zkr)hL9{uplu5a#v!U4-Wp4vRCu)%#hRMhUj0au*{0;&nlLk^i%{uGA#fuDxy(6I!A z9!ij)M!hIaObz8~$5~Megp)7eh@BdFWnPu=BQ(Z-UNwsI)=j0rAg^-ggGV7sW>o_k z!sx_M<8&l^0%h881*Bn$qY_l3qYq)m@Ox0bbX6+x(Iot*wA1yhSW$T=e9_%^G1#Gu zwAnIIRLEapv346Buy~wkzw*`s)|7ga!;P`t@mw|6@b0Jd5x?=43(@JLxLrtm7`uuM zTYcrG#O=lMFR8F+R=LAon_A`BJu4S)`CRo*X&%=y3ZTXDdKdx3o5tU0Nw>3{5Ct7% zSrs(awN)@RPb9;7M`Js|sM(=gjaT(~w20YB=@Y;QV9Tgocnn66h&pS7kU#TMDmaXvcXE z8yK7HA!yjD?6t;8m8@t3E55K7&GSq5xD^yAzPGYdENv@d(T}x=FrpVbUlnkfraipf zmA*%G)cKb3eZ5J&t8rpfaBe65Y88I?sUXforWI|n!rlm;#$b1s=p#;;$@;9(WyZS) z9kpF&59rBqdA337960T0z-7DzMr`(qT1+Ba5LA}cNK0hoGDIZ@izrdSnq=+ z))EEg1#dh7yU8ul(PNJV+ zZQB`H*RUD)?X}llY+9J_#|A_3AE)~#oz$VtFMG)Q?^BgigQe-iKvNF_hl_71GU+}& zsJLYd!fI4n5Bb(5PmQa`42L%}l4Lm59^=-1?3yY-eQZWh-^eIg@z&sROaU6*edXC( zwN>IDHvvW*WfyVP;)Dx_+7NpCKfh-0He)+4B;oAoLEEwaA(LZN8#;aa_B}$Hei)p^ z-a|9ND5rt8r4+4V;4#kyMq6ju?&IPR335n%Yfq4niB$F_qS_6n<53N1BDyW%!f)CV z&fe-fwBuabpGmpHB`kbpliEtmlhLU*Q{S*FLKW5J80jO@d^R5 z1=>U!J>^UHAew+tw!ib2_=<=!j!&MaBhv3=@X4U6dZK7>I(sGkHEn}Hc%@N-EM-Lp z+qT-`W6^XWNt*NwD)DNU@>*2vX)+gs*EwZvVWtA1-L73`X3s{6U=aMIvD}tf{?D+_ zjv(k}nJt-zSmuRHxnq8C=-v)D$>cUI z{*hAicek>z8QF~YsGiNGPKU9((T=)FA#ZK5n%63sOieg1q;Z-y7%bDKHv*>42z(7q zHbg`_8&S2J^PLVE^k{htOS*Bz>)2qkTshsEh6A6oAH%v;{eF$Gsi^(#Wb9cTP|nHm z9sn&I=y)b-F-!s-{oYTnx?p!0I!Xu?fC$N|Mre>qun?l8r5d|6-#Jb+)?O!FgV!l} z5543bql8USNQYt9XbVZUb+WlUwIfOrT&bniqz~`yLC2&oy;5}inrQIMPe%^ldoBvE z*o(({lu_49-lTDw9*y3kU#~mFzZF2|=1mS+)-Z{Ez?|-h%W0tnJVCSpnY`11nii;7 zkuL}GjE+4Ga{E|p99quOhbJO1>JWp8U$k%*C`YyJqg}<>q4_5=@IvF9gX;L`D@}0{ zr}kiU&4f71oQWFYxLzR`pXsQk@Iif^&JhH^uDN31SwHcm_+T!ePVu))q_Y(Obs}IQ znM4VQf63Fe)L3Gkc0_ zC3TLK!V8O*gK(l{$}#X4oU|7g zmOb+Tu2E;6eW)u75<(G?i}!KBr+V0OA85B&C3&x_OqA;D@}~`Y^saw=7C z1Tx%x%!fOgiC}Tfq+^yf5TVW-*R3*-rof4AALl(JiJH>R7-4vW<2C@qY|Bbq{Agp4vfA_!dsB&@hw+ACSUBA zphNhV%{!eFn|sFIia;k|wK9TXqELY{sf_;bPY!_(3+0hn%vNR?G<(XP_pZ&(SmE|M zE|Fs5M^S=o=gmG7p4LVgOA6}M><|wpWLg?jSg(gX7?9V{S1iepi|zSVzsDj|o|`2$ z4*P;CkLJscJ15HAjqUgla?wq<5{#k(jp7<=a#QFvoHEQAiS%G zui^@1f|>qbE4{kg(FYjH{=54qsHh{%O8$dph?TkzP|4E@|7CUnoKcY>_~J{W#4LEq zLegbAYrl*%OWc>){$PDX+`?W2&>@hqHN;(l`P$S-@yVGnne}}bgBYp5h(&a_e`#(sW6|8SpIO;f}lTm*2bs02FdQ@_EqmoxPCp&Za$O>L9 zeQ5%N(erf<^VqJlfO;KY`wF^Bf4+KgXr*q zt|!nD$$)i%9hp2foHVVPbwv8;nTn{{9UOAo5GeZH5^}3PLbgj7^;gg>HkU=Mix@0W z%kArg;|nJX0HVWV+#Wn_13LWz)(ljgWKgO6$7!1QPfXvRZ%>pNhF#J2fp&ireY?VM z+$?hwp)??@xC3QrXu5v!YH2b*e))8YRSu25A8r3HL;FMlmg%Y!Lx~Cu5Kmzlxn8RN zqqECYrCGjG68neA%x>?v)9gqbbO9)Hf+Y1~8#)qHp7!#pT`>I;nfknd;*6e z{Zo?t$K2$02!jM7YEQ2L(n&@~gb#*-Kk7S_J9(ez^SBJ#se@+UEO0t5d%bcE((UAVBO#8kR-L4Ed1BJS3srt?uE1y_-40L8S71dS=L9gjAcI?( zHkr4F6Q<1uyB)s}{Hn4aonG-WGSw1|{>{bdqN6POyZvTeHRpOPPn8=Z9mUs`^+p3TX_gsb>a2zNP?NfzAM;FEFPFZbAdpD9gp2zh@#rQaSYMRfLXzQ1w&o{=3lD2#A zdqj~uOQ9m+(emeyHiAynKJ@K|mw9U<&o~ZGJX{;MiI?*h<`G*1+?fRkeqW3ICHN3E zh-ScD+ZfF6@~#-{fXCiLJEPnC1A~~tkfScP(w<|}Afu9ulJ;ThbbW^XsAies!q7!q zG1l`|)5b)9-97 zq`w0tQosijm{Lzs0ua57%XEUy{=xbcGZ&JBE<4f(-?2WQ(Y|fpmZKS#L4o75>ye_< zp63eDTGL2&z)2(nqlH}DA~eQ3$@OQ%bsvk5&00o#(Y{8caV(!h4GrC2FhIV6<_9-c_#tut zLLy`GjV#AS$)E<+_1Wo5;gtH7(C@tgJ}De%^d*lu43}n7-O_I(|F63#KIZIymU6q- zTawetF7y;SKmKu<741~fe=si#)?p1~Rbb>wAljx{AO=IrynVN=bI^aqwuU3?z)19U zdYlK}M~?j?4CZdB?05iiT%nZjr9a_=ILU-y@K6mggNI69_nwF>C35)9%UQIX5>%KT zL+4FDT4Dvbf=WMy-4lr%@EZWL9~8G(5gnuYY|t^P8i4DXTPjU)9poh#mk7%KA9^^G z7OPMJ@#Vy%vA(2_U+OIMmS)HYB2hrU;8c(Pt*kEEDR6>x&QBT(LS6vuLyq}ukp!=< zJ>=cc9WFx*vdkx>^4`KxvDlQch(5~)nmlQ=d#^z;r0NJ%!&Qg@_~THkwu)hC{K@oH zOqch*cxaReWy?x5$M>`ULZ#)N!ujC!TJDD~7bD48P!TjhNeO-qKH0xGUT1|YDbao?yQ7>WRb#~QaW zqP+vUx2GrT%oIM%hQaRob77Bn3XerJ)_5qXy`|^L4#JIf)Y#@^hkBQ&Tq=zLG&+kx zm!=knBD%11B23GO2J!&GLvQ~l9y+*y|7RUr`jR;O&U*75=3C5v{rJkK9#8+6yY>2V zw_ogH%jAjp<>B-ucxz>ffJ5flLDscxrti6xQ#(3CGQz%de1+%%g<_GKgL94auHq8g9&?AI>yuPJV zAd!bRP(l&Wlv1RG-9mW`P9~=;qEm{<1f2g7zJi;@RmJ{XZacFig(lI0-9YtVUj@b) zK1AEYy6j|gVo(98;qaSMKcYEg-?Yu|H0Ls*ZEUt2B~UB%6@h5~I&ro(q%SKdF2VP9y4h$k`EwQzzBKRyX@1TI81kO`BZV{j)u~7FqLGcDM>@V4JGp z-zXsAh;2%SwK1c;lLOmi%{ViS2eV3VbK5gXX%ai#!Vg_KjDDu%K zrn4z)uJ!o6|G6IkMO#Dht@4gOM57JSXmlD7TpN9nR~)}xJ2Rl?d$zI~$uqD{nXLEn zE8VfToAV~nD0i=~%FZt4ukHEgoJXcNf!SFa6Rh-rW?DY zUgZp-u^XEfSX`dv&oOl=jD^pau-WoFKs&J?Y@CIG&ymIqqRVLA`!c~eXM&JbYY2H! zj?~VSHZ|DLjhLy&lj+x@l6OQO?#y3=S^~6Es}PbkL{KUyD#@$E_u^ARv^^5T z+~hUST*HN{M+TVQr$d!Mr1sn)wFRW1(j!LrFBmQc+0^uL@)ZK>R7-q%kGeoGyPS}K ze#&nMdN~|UOK^tNszI@tzAW*1_6iTsB(^pGI_P`M)3m(@V$y+$4Ipxa#;WJN-{p!P z6D{bpnvC!qW)=mOG5;>iHRyg7On5(@u7h?3E`PIvz$GS22-L_l&<~%Q^*Nd2Up58A z+Pr2=v#OsqbQE8?dQ0Br8Ln~<&)PoZ4|W{F2IXZtyN?JlT_|*K8~Nc|FJ6@te}{vW zXyF}BkhTn2Lx8Jw+;V;Xm#mT_AON!guWcq;{rmvBr^wB4sIDmoMhsmCQKwNg`LT11 zW8w!iJDW^l??>j&2YA4?4tnsK@8}}BZ8sGIpY@7yARiP;0^=GM(#IJSHKF$Wlt#iXFv$3@fVOk zd>LlSwChV+>Y{xd@ya2U_b29`DdGa9QqfzpIv9jV{qQljZEbW=^h$5i#ZM&7x;ID% zc_sBTVnq9P!Y}UxOFRPwC5<`<8S+RH~qMpx$!5#jv zSx|LTf(a1F4iHQ~ldu)sSF#{Yu_}ky$jo98zLp~G^k#B)7qWY>zs)NJECCy!isnZr zU{k3ofRzuqizz2bDGKuMh{@DI<||!cs|#_0gRW~L{$Kv5iNY=JYYZUC+_;fr5lQCh zi|R0c3sBd+2+9Zh=Z#T@1(#wGZW2xM~B%6zbr#_CPp(54%mN;9xFL|4-boSh#!1sCNwpG zGL{9*N^hU%A*2#)rKneT2C*^Vjpn~k_gS2|ECwE2O#36>(sXw?Tpvb|$qeE|r+=u; zIt2LQg^**OQ7zzs9gYbM`2Y+80K;e&)SRR{crTN#g3yoRTQ?3PBWSWK#P#PmPKMn5_5^t`01_hVzZ0eno~1bu=$7a6UoKpakr5)=)$6 z{M3LBY?nqje~ad81fyxc0{($iP<6}SRycgz5B>SQxrqYXnC{Ocvpa!I&J1&eVWA*{ z$COe3C_R2CALo59QnahgWl2OVhbVb~i^DIy?djh-14l^IOAAXR2)=m>w*VUi=~d@> zQtR(L!OO!D8mvrStJlP0-u2=GMoj7m%VAyp4{hfn71((=YM)PB^4M- z@Fz=b@MJa_g#F{5lyD!8-)V>I-Oo3b=Rf8t@d~t+o*_a@0vTQ8X!O~5A(`vsTmNxm z=%4*WtQ-=gM}<9G++kp!j@5z&eWMYky-{vq$E1gZbtnjT|#@Oj2l&> z9JxM=RZD`Ko1y>Wt1={>7pw0T)m*KFKc+P15QgI;?IleDaSTp63@em^{>etn`#xRSc?$^>4ajwrFy7ykn^On{Pgwjw zFq{Y*7lM6RPPkH*E1-P?0jw<#e@Unji2pKL>qrJef#Cy>Y{m!*kMaX!<)uyOgmS!_H3R*V%v-Y#r(~_>;}&>^ka+V^ zk5)O#2z0dXTj&XN_GbGu7q2b^QTC4zZb8IO6+-Im&xk#iRxM_ibTVYU@syXoy(c67 z-;FEQcl0w^gMa4!^uNxXGWk>#wSIn2*tfrUkh%q^garp;f$%ja$_S2Vk=W{)7+{8-{{7kS zcNhXrnlxM>4*PRMpRr=V56l5osqteFMYu{1K<4POEpNMH4nS3%->-*vupd~4Wr%vY z&V)L+dC#m8-MVpZBYIU z3(6bfn#&4{*hDy3`T-fDHmUqdpO#D$Bl7KmQy-W4`wUl|xBZ7dNBZfK^j>6o|57{v zw?QUP!0ESlov{-*2%`A?3E{e7Np}LS_f+8CPXpE@XLkn#bOusAe-J8;y^#1$%Z0rY zFa;+ApVSz_uvBxbcy1}A5O~K!PiDDWAb^xN(YmGj@!G`Hm0t|xXnXjDk ztt|-{Ba?wPJhN`Vw@VY_)$Dqjj@aaByoT42aa|Br^i-)PwZ!_aqYiZXp6J-qa^TRa zGW`m@SbG~r&J8?UF;Np)08V40fKn#i=Q5#haXe)~Q3ZyQhAEJ_Gt;8~t$UmDFI>012T$O9olk!QZTB1rFYuJ6*>oaW1p7J_Vg| zLD)iHzN`42E{3h{f2OEAd3}8#er*yhw87{Vle89K1kDmdAj3BfDMy6LE65g*Y{a(7 zt8xx^F?-jasE8h^J9XWEK3R99VaSy3+xOp|zrmx(%gXFjZ*zr<hq)=q00A!Vb>AR! zTJ5WFklk0{-sW93ygq+kb$L89LB;{sZ>s=12yd?bX9s1$4r-cKZ430)|CBFBc%Bga z^*cuh4qJ1g>RXC!-=iYKl(*7hu9izX6a2G|(x93+T+rwh$yZ%eWE&x* zD}u(20n!y>e01vv;(D3if{p7uu~}8qwE-{|6|r{-aonU7DHR&LFE3D}_`Oif;JSL^ zsp$0f>`Eezd_vW>ay{23F{0-D-`$tLWCIp=&8cfw^X7&o0~@dTOuFl|)hal6)oZeB z`*3{yJe!Tcly^7+_T|^*lgsSEpneq#f_}vIZ5={uvsM}X;?6q1>#J386sql9AU4Ur zw=BeY=C7|#Y^0f&WsB>86Li`JwpI9<*4}%WGY{)eJ)pD!nXr;R{qePS_qOi*dE)Rd z`?+U#c4GoF5tPjPr;_2u!mJWUvnk?!hF7U@HLc!>4iI1}ITV#)Cl+d^fhVr8ozHrP z^QYYceQqrW89GT&uY{=w)z?5i;R8%nEzCGbT%;R*FYv2HLS?!?3`H`{79Drq_RM_D zOM8i6BE}qa!yh3oOavMpKJ7tR;|^x#uWF5n5@d7w@J@=_TCa{css@BMlYs%S7eRDO zmGn)b_@H5xpwMeZ!bidmI2dCAT0m3=;uUP)_uPOKHvaS$Cq2)Kw)lM2gd)(-v|%Z!55mCWQ3`&rOb7JUH|t{s;}f( z7l-fg;)@5j8STCCJ60fn0o5Il;mwe0u=LG|1&(~cK@n)qy4&=@>Chxym!yI=PFk)B}M&CkX+^(ce&u+)Jx~q=$vibc8T;HX||R zO5q$o5>IF>MZJ&VA!CEfD*2Ci8>^V$TuivX0z zxi$Zyc5i>s?`q_VsJ4qhcQS892&^Gc0jtc%i?zur6%Usew(I8YtK!6g9JA~@in*I! z;2I-#UZ7p?_!c4I&;+d{68(I9sViO_a`AKP<^J9$?am}R!6|P7r70T%{PKisj8*lU zsFZ8^!N}|B|J?d5OHQGkw@cfw?8bZXORJ7`#ek&1vOKmn=@feAZ-qiM=emB?*u2S) zrfhX&j^5fu)#xeo8YkR7_GE&@6(ff;CY+J7zpmVHJ0xMgfKh)Dqooq`-r2;hY9Gv z*2J%;FmR!K&a}-c2@8v^AH%wwT{ja!PqWBd2+_3bG$xI^l6WAZHp9y9=rPUeO9Ty)?rI7ysKEsQ2~$>YhvY3H#>+`hlvohFULrnY~kmKbVWBm9v4r?KmA zSGWuN$VF(4)}JGfaSywGWfsX_QD|IeE_o&oJVTf-n+=hdCPR!~)1LoH@8F8_D=)*R z&fV09+X0a@Z_Z|e?vha82(AIA zB5r%Kza8F*-g)IDPViAhJu!UeIxvho(+}L8)1s2=GJF$7W)@`g9t+QzVrt7salj%N zpVUZlbqAhuVCyX9+TJyb z?G&t5iuR=&D!aYd7x8edD9ZKS@HfJvx0o}40F&AD7qCwk*5uIfElQ`bJR;5jj$r*D zX8uBxrRZ!U>Hx*tpQ;nSvTdWEoPe7XT1^P-(nROPB0qat`%Pf&h7bYmkp7bki(St4 zPmbPtpIxu{DkZ&Y-6y%y{E*xDa~#&F-5`%wcl;u%!Hl>sFy|cKoD|i_;dEjG;}&o( ztFs)=(V>S|xplt6b0v=5F?4Y#_WD$CHG5gRqqcd!9*bLo^DI&>5x-oNf=bTncyauq z-IiWBifjGU~YMu9q?y!y5D6!p$fh$P`Fqv27=QAh;NeZ>@j(Hh$Dhjm-qM?8`A#l!&6$E8wXYsMSB(iXxqV;nP_D zC%F_p^50C%iW}s%@2MS%aqO>*2nvL=d@Q?AHoM;>ozgYkM$f3p*sJaGOZ~29&5!ml z>tVVE6?M7rTFi05ouSKpzv~mfnUyuDvNKM>ia?`0Hu*HI5$Hp(q#HVDQYL%L(f6XS zugO>HY2wen>>3epSQ==R3xsp?CNO`X&My?m(V-BceE{(4X9E8*&*7VnKzRrDv8dhk zaW2K>mstR^S@e)vf3I-N&U-aY9-)CXR*y8d+ExLB=sbkaLXA&gB48998lj|eqpjQn0ZX`F z&V8kO3tX~Xfpwk4j$k3N$npSr&g*I~Oq>@0yoBb7(Wj1c&ptd+D6em+r5pFjz&6`q z4th>X@WAmCa;;2YaEhn=>kE(;DHiqg#ogxfr`<|h!tv#tan`5jfK0!-X?X29;sq>x zrO`_D_Da({G!dsyJ7~8V-_*CV(i_2Hi#k0Ju%zZQ7&d7$_$nf>kc=1a_LPWHxJ*K8 z^x8vYAkWKW2qVi=%K{4YgaDwJZ!PtEpsmlB4j1Mt+}*;}U(` z2NEAvr+Xex5ktkR^U}DVCcxEpRlQ2Iu?T|RXnj*=L_aKuye89 zcJsW%(TSk+voX&aTjL#v*U{!r=o?f7!pJp5gV2(5}Dg259^GR+1(3 za>)^#!~@pck2QZAKX21UcLZE&?-+ljdQK$ofzB8qdBmOYqClMa!PrJz7oky6t)sy? zITKWxv&W;DF1_#5JCe^3g6SWb2{qsqHVNrijpT2 znhe=bhk+w!5ZuGnCN-Fn290&Oj+g`I08Dmt!S(E*zJ<1+68D_Ir;5>E=_fn8f;$@?sRM_?|`Bo+be%&-~hF+%fnYK zZSr?PmD7|^8~=*oM8HlPSuz zEWZ}E(E@#r>I+%Nw1S0tPyNpzH*Y8ANb1g(5>JP`nD;rUnPMa~aDU78;NCsurSrJ% zdk*}_gy5PGzGC1DjphoxKQpidORvLD^^I*tZEU+Bcj`9_KYFo^oc}35P3K>!513X# zfThA5x;9yN7?c>2*Cq9rWFJ1exd=Z)YgLE2?fo{78!-2z25>`BxHAV_8gOM%tHa92 zm#Qv#KZ7I8>~8(O!eSuZ>ae##n05fsI$zC8GT_eg{so^4v??m8-H4^ishw{8iD)rH z$u#v{G@82d$tmgb>!rP1i>xbpU!I*V$Cz9U_XJ~R;qxJbMyM*jBFQ#7IUgYKBx+2q z6fh1)Ne*yX%@Ew34k;0?JVjyUZ?@K!_b$5c@bNE)?xg#4X{z_M8WBCtf$)6zaZM(m z?)M+N0>X9yEjlFmhKcig#f*MtZX!DiE!(z8`SGPd^HNaLqcZ#zL9R) zfY*Kf=+CcR&@rcJqh(z!Xy(>I{PG2sWQCz&-?@%ZES`7i5cztB3$vd1m z1{G^LDsf0bC_Lsb>sb@zsJub9(w1L-R^Mu)W@HmwbKz4;WaYvU|6M*@wx$;N6~}k) z)5oL}cT=lSP(oj=a&^p~!S>-v7L@A{1Q`~C4##mIE5FTCd9 zJ`_AV&khm564Qrr48U<;N=R$l<@fuxVAK28+`G4CwZ+SMZ zlyjr)6Y*oWw&5H`djtK)@#)1DwmjQKzY9(bS;;5;rwFeM*R3p0RAzhEkG{D@?X!lZtFzO-G?(eT)~t?Z6bfV9o3Yv!Twh}!YI1u!Ule{Z$^ zE{M{QtV6k_J4Rhnv)ZNMo>o>gL9}^t+kS#?SDgFy@-+@^>yKf6M|B5vh0XJuMTL9K zyvy2K#9*}hpD3$&I*XZeOf*WZ4O$d4Q64;b)SxIcF@N5VoIjoRfy=!6t{P_I-^VF`@n&{o zdQETVFsaD}yI!$#Zn%aP@sRFu%CGAQ{~3OEDR85jWe0C?qQ=m&o$!7r-#t#`0FC+; z1q*QPi;@D04(yE3S6I8<*LnRolS5E(V12*aOUD%dM<;>~Axy8t*f`G%}?OlxaA1{<>7t6_zxLu_r>yMk|jmMwiu<`3!9 zyTTCCD~K?}NKF4p`om@GlM>w|9Rc0XT*M3gWGA7|=!^P`ugu#v@XFYv8 zW8U+OoO&$vF(Qqnd8TVEK;Z)tceVdC3V~(IfeGNN2K3?Y9-49;$dnik6O4Ofy}Hd- zU#$033_+mEKK|$Tj#+;9l;R+l4g+>>8_>etCUC0KMdT?ws%=+!q+J)7MEdmhoOnJk ziwBkmm$SUu44Rw2K6CX@`bW_88PM2|H6d^mVV#vx?~(a|5=t>V>A>j>Gr$l@`mUOHM5cO-o?d1r8hfYFS%On};vzW{ zSX{0ymdE)}Y0#)pn_eu)b8{qG8?!^K-r(n60J{49jrMS_t5G!04f;a| zrUSIkluv)=OLZJq8uC^O%}KQN-t2tZGb4`+!rtjW>?hk#f8Vk(y3dG@u@9pnX|I~C zAzXKBQ>WF6@5L_!Mdbz2|9D{6AuxCozb{1TtiFTQ);wbdw4@!s{FYg>n+k(%#S`3}K? zBE8kPVCTbv<%%PB`4CG#STmV0JgT=`Jh3eB>W=CN-C=d-;qOy1B}ch12Uke?0B&d3 zGmk{MV;)(L>(74epU}Q`kD!-1<0rWyA4ky7yy_oqKfR-qb<)}4h}Fqb&jbxNg6k%LTsx)81eGUGm2wOJ-;`j`H4n#&Y2CNp>@c`B(jF<*;Cntw|gzXiSui z6o?%Rt@SzTn^%()=w)sAK-c}`!luYM@0DpE$t3TcTlo;#Jo18Wu6Wps>Dr6vml_b# z<`>qT<#0QGL0@$tCA~2Hd~a7S&z$zP9>5Y@6{u6KZ&P%y@*}wjq|*o0 z|8%>%ne8mm$2&5bUcgv>1(v)Wf9Z@+>6V21iO%og z-dm|Tju{oJ%J=Y`ai<4{^cWaFU7_T+x{gv-wB`)4zV+7i`61?0^p3Fc8doXYvv7Hu z`HnNUV#g!E^_$1jIWN%!b4>Yfbs^-JW-U7a8P$71!j=wjfYV zcv62M>1j5)4^deIfhXrfwLhT-W!;pI6heTrZyx#H|KKom1Q5^Q6!R484 zS%k23rNlhN!Dn$!?;ObKep3C){vjaqtFP5|7K^3_5L|Ji(+=c>dug>@hg=NeFK>al z*T);3UQKIm_b4dkvL}%A%@t{9yE2)0D}D{l8{PH`7#O=W5q!6DT z!d+#_{xn15liGD}ye4k0p658Ml1#>YYBM+FYVmSP^jGU*#qRU%&p3sRMsmvIn5L9V zPriH8YvQD_3>u1`cM6cpx;;JWLd8ILp{pYL zq2!`sW6V?#pS|sNPE!onSzY}!%*U#p8`j*az#(h#aGf=UxvFNJldKJn(?^8{@KCdM z`vZF(-ly7@cnzVe{C+}KA6xE)4i_S)fKqo-fh$$gD-V25g-u`K`o=jmF>{0=mGD_= zSm0KNl`Y~VBy#UL2?HAp7ebgLYnq2{PktLl?=u%LiHD40zu)gF`L+A~dP)p67#`{0 z8?6H&hlhB2B)hzjoK$etdEOxQN2p(2H(5fnb_)1jyV^av@hp36;aQ@`)vT#hmCri+ z3tT^>zy|5@EaKE8AUOpEc%S`0}hHj~Ykn zb^`+V_>m->;Sp1dQty_Pc)+oXsiAs#{TKg@*Sn!25T;GzHDRSVll*BkTMmu~d z+l9QmPn~LCH&mAmA6)C{+I^wBWQ34t!umCe*f}IKb@k7gb7pk1vuG~JctCqxNE<=q zeB^xOMHyF%T8Z*E(~m*WGS#_#ozgZz4!KGT*EiM@9J64-It14 zTTV#>ri4p+J(7=T%&f?Bc`k8%jESfY@od|~i9N&J!dR?|1NJQ!NF^*EYJ|+djt|iIk8o4HKIM^?{k*h5jW$IV^xT)a?M={KPjq5+|;S-NcSqAcjN*7LJ5w( zHyPs9j%BrZDKz*UT0XYPetFN%AF2+>U-fGMz0wtH^&fO;Z2$Q zI}9_>xZmfQOyzeuDIop(Nef=HR9`~DETq*)UArm08xy|S`b4*^@e1)v0&C*qxP8mH zUEkn2Ztjbeu&wPQdeuowb`x!KH7S}k(5{75ZtoS6<@gJ=s#a)t1BQ4Rum-EV_*ew* z$g1Eo@A%T63Kg3st&rhzEI&{HbblAq2cH*if0)aRtcHApvFw;uHp0R zP;PZ^*E;V=d=S2)3wzXE0}o0~rUT)NUYHwZK3+!Q-Hzym?OjzqB+~OhmX7LF?Gm-k zCt06gAB7a&yrsJSMGJsb;~EcuYsk%d13{4;JHmgXuk|roNadOuO^VMUWQZcMCmOev zOj=>NnD8q))NfyHXMYrS2mboyso3YE%w@0_Tn9{N5?AxjRe;uM^;LneSHRChpHz@P zhhEa5b!WX&Vcm%Fi5(*T0wDB7X@9YOzI6aN{v|Gt;P!0R0kEmo~#d`_d1F8L?K%D&4aDev!Kj!r%UU=>!Z8z@>7b*gtcQ}$XAMs;0?ZRK7nH$C#A4BqYheI}50_h3;G=wy& z&#tt|_blve|B6S>BN^`3NB-*;^7N3?^Pet*APRnkT;M(4V|D6B4Ev=$1nqzNF52lJ zEO(qvs*(%N0|DcIZ;0>`_bc4};MymN^-71+<0>AOI7Vr!}KrE)m)j@aE7|Mk0M-t7Dk@V<_)kW}t+Ys6gz z9Lrp|@TG(Q^*6*$15&9KcqBX>U(em${{*11o1+xbyJ->G7qAr~^GKf{G|Kz$u)1C~ zn}FXseaybZT;5_B{JqYy+io(9d$BC)f1OKvI^^BJb{`7AWcCjPa%kBf1oHO)`Ag{k zw23iF=QsX=1=t;OnrWcOBPhDlr+-$GP}%m^Q8~Q9><;)R*nM}Wr0p`TH!F2a<*vj( zbFttoOugSQHwCsnWQSz1tY15WKm`ip1%_Mt+~;mqlF%LMo?3RnIi<4TS-zQ48HgmCx~Y5kJE zVh1yb3?Ff7I3Cbt+A5EuxeJlF+oZqZY88mvQWPJAY@L{D4_l|}cAHrWknJA3-o3SI z#dYN*sskap@@skAmHmdS9TSx+3<`r+%v0K}P;nQiyUrkfv9qz;F_rDlOiEg3gNU(E&}fBU$fJnW9>7tlhHWPdW#+FHqQPWT^9+ zuv0!I;@acDq3uNjkP2mdlJ+RI%GW2HHMVzifbS+pLyMt3!KVPkHuA~aI}9b5jVRU?%DkoQE7R?T_r!C z5i03izLQIFtk7jVO^PZn%%T5hhnWak*DguFd6>{bcz=JN2*QLoA+_6>B1*v9%smQAGuPXH7YCl5p>?d=Sh z(3nsA&{me|0;}^v@`Eb*%!49osQdDPCUJ~V zFEwF6=akH}*!;nMGn>vgv$+$F`JBFxV(N7n*oT_-|3f%LeUG(OY*TKX5$sQC=~p6y z(dOW=ejC>KD!rJ4y998Z^xrI{zd22#x%lH#pS&I+q>2$Ke$di>jt)0y<&U`~Zc zSFup4;HvUSKo|h}`wNxT%wgtXlnVTn*ur@}PX(8VV$@B>)O5?}3>rzRIC7t~lqhmN z9ADFBHUWEwIfMaAtO#;U7yM7)Nl-$d)G8%k!r-bgDCBSa;ni}Iz$?)}+L2Y?G4LYZ@1n;BaD zBZxCemUWl0!@YlR%o0~Ub#iDdow^1@FS*DS=+@F+)VPS#k-~P1p!vrg{ZwvCMqDd4F;^SKY%i$i6PS1$v3mNFL$y6S?20TkCjXJ^SH;9974;4BZZ{GhsUqe^+O4Qzssf@W> zUk-%M2i?E9o@&VS8jQt=cPV*KKg6*;tKOit<%v+3<%mZO<&$D)=Bd&(ucE4V7}|1#UzlB1gud z^9U1G5wrak07y1oHeZg%x}Q08(BVeba=}7ax8Q5S&gN0>nftOFC$N3YHq2++R>CcM zNF452=U6Uyt;vDQChTy@%3maV6bu}@j1NJ=)RzzuV;L(_WC5vW+jD@zk0i6>h9amc&~Mxn!|{FF<{0fTDLGx2LL`8}PDETJ;|jXb zF2?1Xd521`c{sMy=Nk11CNPOQ?i~(bZQE<2|AY9aJr*vE#Ge?0q7G^2<^me$EmzVE zXo?i|ft1oHg~qW~vXXfcTD0pE4#?JDYBY6rohv+xIF2~&G*F!U)4Myjgg%nEq=Z?B!qh<0poVu=yEW#&l(FBw zQEPt&cohRmcE^~SH~*yw&w$1tMHG;W8ddOZFpYNW^mK_-_hpAXb!Ew^TLZ7BK=H~v zECOMRx{$cOnaIvLG9e_BM?|&`8tOH@4d!Q%k10xhMEvG+Cd-kUAiE>YPmiz2et~L9 znvN0pC2-hxb-tcGhk`SFB-X3G?|u-;b4&P+fPeu`X0tuK3EYD-19BrD5JB`ox(1~F z2?CZtxJEWoDvS~%f$UAsRig;G-O~;a_=<2bmtCK1Z1z^z5AXv`Cjra-Wiku>CPrQ|;&?l#;k^7r-=| z$zdkGJ6!Ogt<}L%XCQ{Lt0W=bbTOuK@VI0%E-+}H-D2w=cRJvIYu2^GonFbBgm@I? z;-O&XDT{c!B0(0<1z(+OL1Ew$R|Ovh+>xeTAcXaYJP}$2FjL>^+z*ChZ_^kE!_7uE zIeODtUObZAv2RkcnJl$Y`RDu?xLCZm-dx^a0MG=(H(c&W$`oNdjJ>I6p5BwSP#O>$ zclpjV{C?}2$secn3p8*kY~SdvV|On32|k4)7}!Dae@ay4_l$ymfYt9D+dvQHGNdF9NO1=t6&C)khJmEU6#?WPv1YtyS;llTGVuw!s)cjU#PlPT|c%Xc&nV+P2U5| zujTG3JQC@-RGnS1vsu)Z*^i2;ubG?&F%{A6Uu$Rnt$8A6Xm$)P;dSz@XFmyPy&TUc9DJhx+^1Ga=?pkLt6%8 zv{GEc9=kPs;6+5`B0&ASTvK#(dSL$>H1U{xQN$c5nXvxj;H$bx2M{rL{TLqHK(L40 zV0k{!yA%&{#d8dTWge?WRbJzFXDGv;Ir*vieQ@FXfT#>7 zv>o<(?fM3E)VX7=Cz}A$WsIFG2f|4F;%I%ZX8CH5ar2q-#n8_TT(2sCt>(Cs zyo#LyZG8uXjWOVuuwx=Q8<=|erb*o=QhF2ZM&69#oYzHc`un4yE6Gbx3F}&A~DnAOu&?Z>$ zlh@dpF>=P9_5=0s8q0Kl3i+)EMT z?|OY)dCwxY7c-vsM$Rv;TywT$;jK!(Lo^! zFY8H-g&VcnmtU%A+gj`XVy8Hn*+zgbnJH`6zdKjU%zYaYwGKted7eIHjv5|)OeU=9 zp#&OaRz%e%WCbd4Oex+-*iU4JgxxtWgwCoP<8<~1PMt^9?(3GORtb3n38ThXgi2)Z1Qtdx~Xnzc?X;gMq8cuRyg(Eeg0eVxmT=Wr+M ztr`yqtTV42KmYlX2ndU0(K&AAoPuwjsl;5tgXn;Y%Ow`!M~WI~nb5?aM0Ljeg)~n` zW93s^V|A(w&_}B*&-BwMv&oe$pVmyEz!pY9<(>8;Rf~Ed7cEq3+Gq@Lj>ecq(PC1N zoW)moTb8y1<+^tWe1$)P?j0#wa^edm! z4-RQlO?kM-Jp76x*)|I>byC)qETgxd_9sJAZ>BDrG-Gp&Bj54>d~Yf0!j<16yw;t>m-B zuU~78rC|l>mZy!+YoM~44EQ1I3}>?M%i4mUW09JvTb<4+{Fqo<$Z8`YhBx`RTcE>k zMIod-ht(itP5xPF&K>lx-dPdZM7<^BvLhaPX}+FNjCR(nrXJoEc{mDEG#^*~()Z(G z+}i(&J@%1}>4La`!P)9B)WbLH>F2kQiX6M@1Ce07tDX<}NxcvP9!x8750}$rJ8FaH zg&NgD>Pk>Y$O=`&I)oYaLlFzJQiEV#4Xp}0B2N*p~gA2jm|@#%2Q4e#0hcKaM93evWv-z*y4Dh8R>cPWEx zsq%Yo2QT(luXaf+-O;&ZDxy^B#(*tUswU-C|3KyQbB!L?w$^$n0OdJ;`zg`JTw?Cr zmy=&hJ+17qA-B9BVDvXfNVh@x1DAsur;Z$UAT9g+h2ZSMchr|o!-bNr+eYjv96 z@1p!wk$BEP;9z4GX8oSey^jJ5TWKgVYF1f1DYTaMLb~?>@+c1rTI7;XWd(FI;Q;aO zFZk>u`tw7jV&#XL2)O^xE4x2jiWMXI>o@oL-X^NRIm+!m?ce`4JrOxp+3(+9LH-hN zK0<-K_g}8hk#2pcK_CC?Dwzq2SDg|4chh|C1quKCo75%r3*=aC|H?7qdPh$e_oVT$ zL_+wVceJs8_39qYKInTLx<85P;@0NHC)1PMKD*ahYVNOIwDfQ9%fp9|yW8s;=Hr_b zRj7&HZKW?W(OMR>l^&To`K4HO?qq4-D?}t^M?R1Kxh)2_OBzHNPvOlmN8cAY!7NC~ zb~(S-y%n+&vsJMyIlNKjhpQ4qtLVezMZTH;P(I<8K1x>oX~N?C#ZKi&6kvuajupW?rHDB$3wSpWUGvy4O} zQrtF)n7uD61>-N(l1Uv)_Zs&^Q}zyVE%AO2!PoWJz1xm(+cCmMOtr^dZv$acGrh zj|Au5XnLRqb3GFDj^p_7=0b@+o2Xz?ij^z)aPGa^BXE0!t@lQ{&plP^h5i;AT$@u~ z&&jWDU<*o0nJ043-TFmKlzj+*YzOQ)xKGX8pX*JwuzQJupp|axG z&XD`&d|jH=*hle|ViZ|6JKj7`lkSVZY*1y?Z^L!x37K1C+!`6vew!2~=+nuZMXmYgMFbwKmObrEycU;*P_y^6VAYKX>lEA6_HJT*soj_+L9XUJlM| zxyu@VUq)<*7o&?e|FVKA{oyhG@8bTx+yTd=TK(vczpNu)G&~0FBJ%fQcman=bXa{O z&E7%%&!=JGG1w`>pX2?Xm({>1;bjVsVc$C<|M?OwFr2u$x;g&391Z4xp#-yl^1oVN zWa?yK+oWfy{&krb4&prLv!-GHVylr+$5Mk;p=}WL*X2uyl{4x7p7F0Q{Qv92`&JMo X+foIkc5(3TgMX@unhLMv@P7XXV kortex_examples - 2.2.0 - THe kortex package that act as a robot's driver. + 2.2.2 + Examples to show usage of core kortex_arm_driver services and topics. - + Hugo Lamontagne + Alexandre Vannobel + BSD diff --git a/kortex_examples/readme.md b/kortex_examples/readme.md index 08fa2943..6b875d37 100644 --- a/kortex_examples/readme.md +++ b/kortex_examples/readme.md @@ -15,10 +15,11 @@ 1. [Before running an example](#first_of_all) -2. [Actuator configuration examples](#actuator_config) -3. [Full arm movement examples](#full_arm) -4. [Vision module configuration examples](#vision_config) -5. [MoveIt! examples](#move_it) +2. [Understanding the ways to use a Kortex arm with ROS](#the_ways) +3. [Actuator configuration examples](#actuator_config) +4. [Full arm movement examples](#full_arm) +5. [Vision module configuration examples](#vision_config) +6. [MoveIt! examples](#move_it) @@ -27,10 +28,54 @@ Before you run any example, make sure : - You have already built the packages using `catkin_make`. -- You are physically connected to an arm (or you are connected over Wi-Fi). -- You have started the `kortex_driver` node by following the [instructions](../kortex_driver/readme.md). +- You are physically connected to an arm (or you are connected over Wi-Fi) and you have started the `kortex_driver` node by following the [instructions](../kortex_driver/readme.md), or you have started the arm in simulation following the [instructions](../kortex_gazebo/readme.md). - The node started correctly and without errors. + +## The ways to use a Kortex arm with ROS + +There are a couple ways to use a Kortex arm with ROS, may it be in simulation or with a real arm. + +1. Using the auto-generated services and topics + + The driver auto-generates ROS services based on the C++ Kortex API, so every API call has its ROS equivalent. Some topics (not auto-generated) are also offered for convenience. You can read more about services, topics and notifications [here](../kortex_driver/readme.md#services). + + **With a real arm**, the auto-generated wrapper translates ROS requests to Kortex API requests (Protobuf), and translated responses back to ROS structures. + + ![](./img/services_real_arm.png) + + **In simulation**, the same services and topics are advertised by the kortex_driver node, but instead of translating to Kortex API and forwarding to an arm, the message either goes through on our own simulator (if the handler for the given service is implemented) or a default response is sent back and a warning printed. + + ![](./img/services_sim.png) + + Only a couple "core" services handlers have been implemented in simulation (mostly the ones that make the robot move and stop), namely: + - PlayJointTrajectory and the REACH_JOINT_ANGLES action type (to reach an angular goal) + - PlayCartesianTrajectory and the REACH_POSE action type (to reach a Cartesian goal) + - SendGripperCommand and the SEND_GRIPPER_COMMAND action type (to actuate the gripper) + - SendJointSpeedsCommand (for joint velocity control) + - ApplyEmergencyStop and Stop (to stop the robot) + - The Actions interface (ExecuteAction, ExecuteActionFromReference, CreateAction, DeleteAction, UpdateAction, StopAction). + + The simulated SendTwistCommand service has a POC implementation, we decided it is not stable enough to be activated by default. You can uncomment the kortex_arm_driver.cpp simulation handler to re-enable it and try it yourself. The same goes for the Cartesian velocity topic. + + There is no plan to add more simulated services for now, but any user can write his own implementation of a Kortex ROS Service and enable the handler for it (let's say you want to simulate an Interconnect Expansion GPIO device, or a Vision device). The kortex_arm_driver.cpp file should provide all guidelines as to how to define your handler, and you are welcome to open an issue if you want more information on simulation handlers. + +2. Using MoveIt + + The kortex_driver offers a FollowJointTrajectory Action Server and a GripperCommand Action Server (when a gripper is used) and the MoveIt configuration files are stored for all configurations in kortex_move_it_config. This enables users to use the MoveIt Commander, or the MoveIt Python or C++ interfaces to control the arm with the motion planning framework. + + ![](./img/moveit.png) + + **With a real arm**, the FollowJointTrajectory Action Server uses the Kortex API `PlayPreComputedJointTrajectory`. This call expects a full joint trajectory interpolated at a 1ms timestep, because the arm takes the trajectory as is, verifies it respects all velocity and acceleration constraints and then executes it as a low-level trajectory. Because of this timestep constraint, the MoveIt OMPL planning pipeline has an additional step which uses the `industrial_trajectory_filters/UniformSampleFilter` to interpolate the MoveIt output with a 1ms-timestep. Any timestep that provides a wrong velocity or acceleration causes the whole trajectory to be rejected. The velocity and acceleration limits in the configuration files have been tuned so no trajectory should yield such values, but if you experience trajectory rejection problems, you can tune down those parameters. + + **In simulation**, the FollowJointTrajectory and GripperCommand Action Servers are the ones spawned by the ros_controllers used with Gazebo. They don't need 1ms-timestep, but no option was added in MoveIt to switch between simulated or real action servers, so the same interpolator is used in simulation although it is not required. The Gen3 Intel Realsense camera is not simulated. + +3. Low-level control + + **With a real arm**, the low-level control functions have not been added to the Kortex API wrapper because the arm absolutely needs 1kHz control, otherwise it jerks. As ROS is not really real-time friendly, we chose not to offer those functions. + + **In simulation**, the ros_controllers used with Gazebo can be directly controlled with their associated topics if you prefer controlling the joints directly without using the simulation handlers, but be aware that this interface is not accessible with the real arm! The code you write that way will need to be changed significantly to be used with a real arm. + ## Actuator configuration examples diff --git a/kortex_examples/src/full_arm/example_cartesian_poses_with_notifications.cpp b/kortex_examples/src/full_arm/example_cartesian_poses_with_notifications.cpp index 53baf774..48381c68 100644 --- a/kortex_examples/src/full_arm/example_cartesian_poses_with_notifications.cpp +++ b/kortex_examples/src/full_arm/example_cartesian_poses_with_notifications.cpp @@ -297,6 +297,4 @@ int main(int argc, char **argv) ros::param::set("/kortex_examples_test_results/cartesian_poses_with_notifications_cpp", success); return success ? 0 : 1; - - return 0; } \ No newline at end of file diff --git a/kortex_examples/src/full_arm/example_cartesian_poses_with_notifications.py b/kortex_examples/src/full_arm/example_cartesian_poses_with_notifications.py index d5af91b4..2c211ac2 100755 --- a/kortex_examples/src/full_arm/example_cartesian_poses_with_notifications.py +++ b/kortex_examples/src/full_arm/example_cartesian_poses_with_notifications.py @@ -197,6 +197,7 @@ def main(self): req = ExecuteActionRequest() req.input.oneof_action_parameters.reach_pose.append(my_constrained_pose) req.input.name = "pose1" + req.input.handle.action_type = ActionType.REACH_POSE req.input.handle.identifier = 1001 rospy.loginfo("Sending pose 1...") diff --git a/kortex_examples/src/full_arm/example_full_arm_movement.cpp b/kortex_examples/src/full_arm/example_full_arm_movement.cpp index 2ed97ee0..8459f123 100644 --- a/kortex_examples/src/full_arm/example_full_arm_movement.cpp +++ b/kortex_examples/src/full_arm/example_full_arm_movement.cpp @@ -10,6 +10,7 @@ * */ #include +#include #include "ros/ros.h" #include @@ -23,9 +24,39 @@ #include #include #include +#include +#include +#include #define HOME_ACTION_IDENTIFIER 2 +std::atomic last_action_notification_event{0}; + +void notification_callback(const kortex_driver::ActionNotification& notif) +{ + last_action_notification_event = notif.action_event; +} + +bool wait_for_action_end_or_abort() +{ + while (ros::ok()) + { + if (last_action_notification_event.load() == kortex_driver::ActionEvent::ACTION_END) + { + ROS_INFO("Received ACTION_END notification"); + return true; + } + else if (last_action_notification_event.load() == kortex_driver::ActionEvent::ACTION_ABORT) + { + ROS_INFO("Received ACTION_ABORT notification"); + return false; + } + ros::spinOnce(); + } +} + + + bool example_clear_faults(ros::NodeHandle n, std::string robot_name) { ros::ServiceClient service_client_clear_faults = n.serviceClient("/" + robot_name + "/base/clear_faults"); @@ -48,6 +79,7 @@ bool example_home_the_robot(ros::NodeHandle n, std::string robot_name) { ros::ServiceClient service_client_read_action = n.serviceClient("/" + robot_name + "/base/read_action"); kortex_driver::ReadAction service_read_action; + last_action_notification_event = 0; // The Home Action is used to home the robot. It cannot be deleted and is always ID #2: service_read_action.request.input.identifier = HOME_ACTION_IDENTIFIER; @@ -76,7 +108,7 @@ bool example_home_the_robot(ros::NodeHandle n, std::string robot_name) return false; } - return true; + return wait_for_action_end_or_abort(); } bool example_set_cartesian_reference_frame(ros::NodeHandle n, std::string robot_name) @@ -101,6 +133,7 @@ bool example_set_cartesian_reference_frame(ros::NodeHandle n, std::string robot_ bool example_send_cartesian_pose(ros::NodeHandle n, std::string robot_name) { + last_action_notification_event = 0; // Get the actual cartesian pose to increment it // You can create a subscriber to listen to the base_feedback // Here we only need the latest message in the topic though @@ -121,10 +154,10 @@ bool example_send_cartesian_pose(ros::NodeHandle n, std::string robot_name) // Creating the target pose service_play_cartesian_trajectory.request.input.target_pose.x = current_x; service_play_cartesian_trajectory.request.input.target_pose.y = current_y; - service_play_cartesian_trajectory.request.input.target_pose.z = current_z + 0.15; + service_play_cartesian_trajectory.request.input.target_pose.z = current_z + 0.10; service_play_cartesian_trajectory.request.input.target_pose.theta_x = current_theta_x; service_play_cartesian_trajectory.request.input.target_pose.theta_y = current_theta_y; - service_play_cartesian_trajectory.request.input.target_pose.theta_z = current_theta_z + 35; + service_play_cartesian_trajectory.request.input.target_pose.theta_z = current_theta_z; kortex_driver::CartesianSpeed poseSpeed; poseSpeed.translation = 0.1; @@ -145,11 +178,12 @@ bool example_send_cartesian_pose(ros::NodeHandle n, std::string robot_name) return false; } - return true; + return wait_for_action_end_or_abort(); } bool example_send_joint_angles(ros::NodeHandle n, std::string robot_name, int degrees_of_freedom) { + last_action_notification_event = 0; // Initialize the ServiceClient ros::ServiceClient service_client_play_joint_trajectory = n.serviceClient("/" + robot_name + "/base/play_joint_trajectory"); kortex_driver::PlayJointTrajectory service_play_joint_trajectory; @@ -179,7 +213,7 @@ bool example_send_joint_angles(ros::NodeHandle n, std::string robot_name, int de return false; } - return true; + return wait_for_action_end_or_abort(); } bool example_send_gripper_command(ros::NodeHandle n, std::string robot_name, double value) @@ -205,7 +239,7 @@ bool example_send_gripper_command(ros::NodeHandle n, std::string robot_name, dou ROS_ERROR("%s", error_string.c_str()); return false; } - + std::this_thread::sleep_for(std::chrono::milliseconds(500)); return true; } @@ -262,6 +296,23 @@ int main(int argc, char **argv) } //******************************************************************************* + // Subscribe to the Action Topic + ros::Subscriber sub = n.subscribe("/" + robot_name + "/action_topic", 1000, notification_callback); + + // We need to call this service to activate the Action Notification on the kortex_driver node. + ros::ServiceClient service_client_activate_notif = n.serviceClient("/" + robot_name + "/base/activate_publishing_of_action_topic"); + kortex_driver::OnNotificationActionTopic service_activate_notif; + if (service_client_activate_notif.call(service_activate_notif)) + { + ROS_INFO("Action notification activated!"); + } + else + { + std::string error_string = "Action notification publication failed"; + ROS_ERROR("%s", error_string.c_str()); + success = false; + } + //******************************************************************************* // Make sure to clear the robot's faults else it won't move if it's already in fault success &= example_clear_faults(n, robot_name); @@ -270,7 +321,6 @@ int main(int argc, char **argv) //******************************************************************************* // Move the robot to the Home position with an Action success &= example_home_the_robot(n, robot_name); - std::this_thread::sleep_for(std::chrono::milliseconds(10000)); //******************************************************************************* //******************************************************************************* @@ -279,7 +329,6 @@ int main(int argc, char **argv) if (is_gripper_present) { success &= example_send_gripper_command(n, robot_name, 0.0); - std::this_thread::sleep_for(std::chrono::milliseconds(2000)); } //******************************************************************************* @@ -290,14 +339,12 @@ int main(int argc, char **argv) // Example of cartesian pose // Let's make it move in Z success &= example_send_cartesian_pose(n, robot_name); - std::this_thread::sleep_for(std::chrono::milliseconds(10000)); //******************************************************************************* //******************************************************************************* // Example of angular position // Let's send the arm to vertical position success &= example_send_joint_angles(n, robot_name, degrees_of_freedom); - std::this_thread::sleep_for(std::chrono::milliseconds(10000)); //******************************************************************************* //******************************************************************************* @@ -306,7 +353,6 @@ int main(int argc, char **argv) if (is_gripper_present) { success &= example_send_gripper_command(n, robot_name, 0.5); - std::this_thread::sleep_for(std::chrono::milliseconds(2000)); } //******************************************************************************* diff --git a/kortex_examples/src/full_arm/example_full_arm_movement.py b/kortex_examples/src/full_arm/example_full_arm_movement.py index 81449913..14868b1f 100755 --- a/kortex_examples/src/full_arm/example_full_arm_movement.py +++ b/kortex_examples/src/full_arm/example_full_arm_movement.py @@ -13,6 +13,7 @@ import sys import rospy +import time from kortex_driver.srv import * from kortex_driver.msg import * @@ -30,6 +31,10 @@ def __init__(self): rospy.loginfo("Using robot_name " + self.robot_name + " , robot has " + str(self.degrees_of_freedom) + " degrees of freedom and is_gripper_present is " + str(self.is_gripper_present)) + # Init the action topic subscriber + self.action_topic_sub = rospy.Subscriber("/" + self.robot_name + "/action_topic", ActionNotification, self.cb_action_topic) + self.last_action_notif_type = None + # Init the services clear_faults_full_name = '/' + self.robot_name + '/base/clear_faults' rospy.wait_for_service(clear_faults_full_name) @@ -58,11 +63,44 @@ def __init__(self): send_gripper_command_full_name = '/' + self.robot_name + '/base/send_gripper_command' rospy.wait_for_service(send_gripper_command_full_name) self.send_gripper_command = rospy.ServiceProxy(send_gripper_command_full_name, SendGripperCommand) + + activate_publishing_of_action_notification_full_name = '/' + self.robot_name + '/base/activate_publishing_of_action_topic' + rospy.wait_for_service(activate_publishing_of_action_notification_full_name) + self.activate_publishing_of_action_notification = rospy.ServiceProxy(activate_publishing_of_action_notification_full_name, OnNotificationActionTopic) except: self.is_init_success = False else: self.is_init_success = True + def cb_action_topic(self, notif): + self.last_action_notif_type = notif.action_event + + def wait_for_action_end_or_abort(self): + while not rospy.is_shutdown(): + if (self.last_action_notif_type == ActionEvent.ACTION_END): + rospy.loginfo("Received ACTION_END notification") + return True + elif (self.last_action_notif_type == ActionEvent.ACTION_ABORT): + rospy.loginfo("Received ACTION_ABORT notification") + return False + else: + time.sleep(0.01) + + def example_subscribe_to_a_robot_notification(self): + # Activate the publishing of the ActionNotification + req = OnNotificationActionTopicRequest() + rospy.loginfo("Activating the action notifications...") + try: + self.activate_publishing_of_action_notification(req) + except rospy.ServiceException: + rospy.logerr("Failed to call OnNotificationActionTopic") + return False + else: + rospy.loginfo("Successfully activated the Action Notifications!") + + rospy.sleep(1.0) + return True + def example_clear_faults(self): try: self.clear_faults() @@ -76,6 +114,7 @@ def example_clear_faults(self): def example_home_the_robot(self): # The Home Action is used to home the robot. It cannot be deleted and is always ID #2: + self.last_action_notif_type = None req = ReadActionRequest() req.input.identifier = self.HOME_ACTION_IDENTIFIER try: @@ -95,9 +134,10 @@ def example_home_the_robot(self): rospy.logerr("Failed to call ExecuteAction") return False else: - return True + return self.wait_for_action_end_or_abort() def example_set_cartesian_reference_frame(self): + self.last_action_notif_type = None # Prepare the request with the frame we want to set req = SetCartesianReferenceFrameRequest() req.input.reference_frame = CartesianReferenceFrame.CARTESIAN_REFERENCE_FRAME_MIXED @@ -116,6 +156,7 @@ def example_set_cartesian_reference_frame(self): return True def example_send_cartesian_pose(self): + self.last_action_notif_type = None # Get the actual cartesian pose to increment it # You can create a subscriber to listen to the base_feedback # Here we only need the latest message in the topic though @@ -124,10 +165,10 @@ def example_send_cartesian_pose(self): req = PlayCartesianTrajectoryRequest() req.input.target_pose.x = feedback.base.commanded_tool_pose_x req.input.target_pose.y = feedback.base.commanded_tool_pose_y - req.input.target_pose.z = feedback.base.commanded_tool_pose_z + 0.15 + req.input.target_pose.z = feedback.base.commanded_tool_pose_z + 0.10 req.input.target_pose.theta_x = feedback.base.commanded_tool_pose_theta_x req.input.target_pose.theta_y = feedback.base.commanded_tool_pose_theta_y - req.input.target_pose.theta_z = feedback.base.commanded_tool_pose_theta_z + 35 + req.input.target_pose.theta_z = feedback.base.commanded_tool_pose_theta_z pose_speed = CartesianSpeed() pose_speed.translation = 0.1 @@ -145,9 +186,10 @@ def example_send_cartesian_pose(self): rospy.logerr("Failed to call PlayCartesianTrajectory") return False else: - return True + return self.wait_for_action_end_or_abort() def example_send_joint_angles(self): + self.last_action_notif_type = None # Create the list of angles req = PlayJointTrajectoryRequest() # Here the arm is vertical (all zeros) @@ -165,11 +207,10 @@ def example_send_joint_angles(self): rospy.logerr("Failed to call PlayJointTrajectory") return False else: - return True + return self.wait_for_action_end_or_abort() def example_send_gripper_command(self, value): # Initialize the request - # This works for the Robotiq Gripper 2F_85 # Close the gripper req = SendGripperCommandRequest() finger = Finger() @@ -187,6 +228,7 @@ def example_send_gripper_command(self, value): rospy.logerr("Failed to call SendGripperCommand") return False else: + time.sleep(0.5) return True def main(self): @@ -202,11 +244,15 @@ def main(self): # Make sure to clear the robot's faults else it won't move if it's already in fault success &= self.example_clear_faults() #******************************************************************************* + + #******************************************************************************* + # Activate the action notifications + success &= self.example_subscribe_to_a_robot_notification() + #******************************************************************************* #******************************************************************************* # Move the robot to the Home position with an Action success &= self.example_home_the_robot() - rospy.sleep(10.0) #******************************************************************************* #******************************************************************************* @@ -214,9 +260,8 @@ def main(self): # Let's fully open the gripper if self.is_gripper_present: success &= self.example_send_gripper_command(0.0) - rospy.sleep(2.0) else: - rospy.logwarn("No gripper is present on the arm.") + rospy.logwarn("No gripper is present on the arm.") #******************************************************************************* #******************************************************************************* @@ -226,14 +271,12 @@ def main(self): # Example of cartesian pose # Let's make it move in Z success &= self.example_send_cartesian_pose() - rospy.sleep(10.0) #******************************************************************************* #******************************************************************************* # Example of angular position # Let's send the arm to vertical position success &= self.example_send_joint_angles() - rospy.sleep(10.0) #******************************************************************************* #******************************************************************************* @@ -241,7 +284,6 @@ def main(self): # Let's close the gripper at 50% if self.is_gripper_present: success &= self.example_send_gripper_command(0.5) - rospy.sleep(2.0) else: rospy.logwarn("No gripper is present on the arm.") #******************************************************************************* diff --git a/kortex_gazebo/launch/spawn_kortex_robot.launch b/kortex_gazebo/launch/spawn_kortex_robot.launch index d475d2ea..bc0f550a 100644 --- a/kortex_gazebo/launch/spawn_kortex_robot.launch +++ b/kortex_gazebo/launch/spawn_kortex_robot.launch @@ -25,13 +25,10 @@ - - - - + @@ -87,49 +84,39 @@ - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + @@ -150,32 +137,30 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/kortex_gazebo/package.xml b/kortex_gazebo/package.xml index 060b1d94..850ac4da 100644 --- a/kortex_gazebo/package.xml +++ b/kortex_gazebo/package.xml @@ -1,12 +1,12 @@ kortex_gazebo - 2.2.0 + 2.2.2

Gazebo simulation package for Kortex robots

-

This package contains launch files to spawn the Kortex robot in Gazebo and visualize it in RViz

+

This package contains launch files to spawn the Kortex robot in Gazebo and visualize it in RViz, as well as configuration files.

Alexandre Vannobel - + BSD catkin roslaunch diff --git a/kortex_gazebo/readme.md b/kortex_gazebo/readme.md index 206a55b9..ca3c3391 100644 --- a/kortex_gazebo/readme.md +++ b/kortex_gazebo/readme.md @@ -10,7 +10,7 @@ * * --> -# Kortex Gazebo (**EXPERIMENTAL**) +# Kortex Gazebo ## Overview This package contains files to simulate the Kinova Gen3 and Gen3 lite robots in Gazebo. @@ -25,18 +25,18 @@ Maintainer: Kinova inc. support@kinovarobotics.com** This package has been tested under ROS Kinetic, Gazebo 7 and Ubuntu 16.04 and under ROS Melodic, Gazebo 9 and Ubuntu 18.04. -## Why **"EXPERIMENTAL"**? +## A word on stability of the models -The simulated arm has been tested and is stable in mid and high-inertia configurations and in most of its workspace, but the PID gains specified in the [configuration file](../kortex_control/arms/gen3/config/joint_position_controllers.yaml) do not work well in very low-inertia configurations (when the arm is vertical, or almost vertical). Hence, since some tuning still needs to be done on the gains, the package is tagged as **experimental**. +The arms's controllers are simulated with the `gazebo_ros_control` package, which provides PID effort controllers for every joint. It is not an exact simulation of the real arms's behaviour. The simulated arms are stable in most of their workspace, although we have seen the Gen3 be a bit less stable in a very low inertia position (vertical). The gains are set in .yaml files in the `kortex_control` package, so they can be modified by end users. Other disclaimers : - The simulation has not been tested with simulated payload. - - No characterization was done to compare and quantify the performance of the simulated controllers and the real arm's controllers. The simulation only offers a **visually comparable experience** to the real arm. + - No characterization was done to compare and quantify the performance of the simulated controllers and the real arm's controllers. The simulation only offers a **visually comparable experience** to the real arms. - Very rarely, the base (fixed to the world frame) seems to lose its fixation and the arm goes unstable. We are currently looking for the root cause of this behavior, but we found that clicking **Edit ---> Reset Model Poses** (Shift + Ctrl + R) in Gazebo is a workaround. ## Usage -The [spawn_kortex_robot.launch file](launch/spawn_kortex_robot.launch) launches the arm simulation in [Gazebo](http://gazebosim.org), with [ros_control](http://wiki.ros.org/ros_control) controllers and optionally [MoveIt!](https://moveit.ros.org/). +The [spawn_kortex_robot.launch file](launch/spawn_kortex_robot.launch) launches the arm simulation in [Gazebo](http://gazebosim.org), with [ros_control](http://wiki.ros.org/ros_control) controllers and [MoveIt!](https://moveit.ros.org/). The launch can be parametrized with arguments : **Arguments**: @@ -70,24 +70,19 @@ Gazebo loads an empty world an first, then the `spawn_model` node from the [gaze ## Controllers -### JointTrajectoryController with MoveIt! support - The simulated arm is controlled with a `effort_controllers/JointTrajectoryController` from [ros_controllers](http://wiki.ros.org/ros_controllers). This controller offers a [FollowJointTrajectory](http://wiki.ros.org/joint_trajectory_controller) interface to control the simulated arm, which is configured with [MoveIt!](http://docs.ros.org/kinetic/api/moveit_tutorials/html/index.html) so the trajectories outputed by the `move_group` node are sent to the robot in Gazebo and executed. -The RViz Motion Planning plugin offers simple motion planning support for the simulated robot. See the [kortex_move_it_config documentation](../kortex_move_it_config/readme.md) for more details. - -See the [kortex_control package documentation](../kortex_control/readme.md) for more details. +The RViz Motion Planning plugin offers simple motion planning support for the simulated robot. See the [kortex_move_it_config documentation](../kortex_move_it_config/readme.md) for more details. -### Individual JointPositionController's for each joint +There are also individual JointPositionController's for every joint, stopped by default. These are used by the kortex_arm_driver node to do velocity control. -The simulated arm is controlled with one `effort_controllers/JointPositionController` per joint. -These controllers offer a simpler topic interface to control the simulated arm joint by joint. These controllers cannot be used with MoveIt!, which needs a `FollowJointTrajectory` interface. +See the [kortex_driver package documentation](../kortex_driver/readme.md) for more details on how to use the simulated arm. ## Initialization script The package also uses a [Python script](./scripts/home_robot.py) to home the robot after the robot has been spawned. -Gazebo is **launched with paused physics** when using the trajectory controller. Otherwise, the arm would fall to the ground because the controllers are not fully loaded when the robot is spawned in the simulator. -When everything is well loaded, the script unpauses Gazebo's physics and uses MoveIt! to home the robot. +Gazebo is **launched with paused physics**. Otherwise, the arm would fall to the ground because the controllers are not fully loaded when the robot is spawned in the simulator. +When everything is well loaded, the script unpauses Gazebo's physics and executes the robot's Home action. ## Plugins diff --git a/kortex_gazebo/scripts/home_robot.py b/kortex_gazebo/scripts/home_robot.py index c95c0a92..26ef88f8 100755 --- a/kortex_gazebo/scripts/home_robot.py +++ b/kortex_gazebo/scripts/home_robot.py @@ -1,74 +1,79 @@ #!/usr/bin/env python -# Software License Agreement (BSD License) -# -# Copyright (c) 2013, 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 SRI International 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, Mike Lautman - -# Inspired from http://docs.ros.org/kinetic/api/moveit_tutorials/html/doc/move_group_python_interface/move_group_python_interface_tutorial.html -# Modified by Alexandre Vannobel to initialize simulated Kinova Gen3 robot in Gazebo - import sys import time import rospy -import moveit_commander -import moveit_msgs.msg -import geometry_msgs.msg from std_srvs.srv import Empty +from kortex_driver.msg import ActionNotification, ActionEvent +from kortex_driver.srv import ReadAction, ReadActionRequest, ExecuteAction, ExecuteActionRequest class ExampleInitializeGazeboRobot(object): - """home_robot""" + """Unpause Gazebo and home robot""" + def __init__(self): # Initialize the node - super(ExampleInitializeGazeboRobot, self).__init__() - rospy.init_node('init_robot') + self.HOME_ACTION_IDENTIFIER = 2 + self.last_action_notif_type = None try: - # Create the MoveItInterface necessary objects - moveit_commander.roscpp_initialize(sys.argv) - group_name = "arm" - self.robot = moveit_commander.RobotCommander() - self.scene = moveit_commander.PlanningSceneInterface() - self.group = moveit_commander.MoveGroupCommander(group_name) - except Exception as e: - rospy.logerr(e) + self.robot_name = rospy.get_param('~robot_name') + self.action_topic_sub = rospy.Subscriber("/" + self.robot_name + "/action_topic", ActionNotification, self.cb_action_topic) + + # Wait for the driver to be initialised + while not rospy.has_param("/" + self.robot_name + "/is_initialized"): + time.sleep(0.1) + + # Init the services + read_action_full_name = '/' + self.robot_name + '/base/read_action' + rospy.wait_for_service(read_action_full_name) + self.read_action = rospy.ServiceProxy(read_action_full_name, ReadAction) + + execute_action_full_name = '/' + self.robot_name + '/base/execute_action' + rospy.wait_for_service(execute_action_full_name) + self.execute_action = rospy.ServiceProxy(execute_action_full_name, ExecuteAction) + except rospy.ROSException as e: self.is_init_success = False else: self.is_init_success = True + def cb_action_topic(self, notif): + self.last_action_notif_type = notif.action_event + + def wait_for_action_end_or_abort(self): + while not rospy.is_shutdown(): + if (self.last_action_notif_type == ActionEvent.ACTION_END): + rospy.loginfo("Received ACTION_END notification") + return True + elif (self.last_action_notif_type == ActionEvent.ACTION_ABORT): + rospy.loginfo("Received ACTION_ABORT notification") + return False + else: + time.sleep(0.01) + def home_the_robot(self): - # Home the robot - self.group.set_named_target("home") - return self.group.go(wait=True) + # The Home Action is used to home the robot. It cannot be deleted and is always ID #2: + self.last_action_notif_type = None + req = ReadActionRequest() + req.input.identifier = self.HOME_ACTION_IDENTIFIER + + try: + res = self.read_action(req) + except rospy.ServiceException: + rospy.logerr("Failed to call ReadAction") + return False + # Execute the HOME action if we could read it + else: + # What we just read is the input of the ExecuteAction service + req = ExecuteActionRequest() + req.input = res.output + rospy.loginfo("Sending the robot home...") + try: + self.execute_action(req) + except rospy.ServiceException: + rospy.logerr("Failed to call ExecuteAction") + return False + else: + return self.wait_for_action_end_or_abort() def main(): try: @@ -79,21 +84,19 @@ def main(): pass # Unpause the physics - # This will let MoveIt finish its initialization - rospy.loginfo("Unpausing") + rospy.loginfo("Unpausing Gazebo...") rospy.wait_for_service('/gazebo/unpause_physics') unpause_gazebo = rospy.ServiceProxy('/gazebo/unpause_physics', Empty) resp = unpause_gazebo() - rospy.loginfo("Unpaused") + rospy.loginfo("Unpaused Gazebo.") example = ExampleInitializeGazeboRobot() - rospy.loginfo("Created example") success = example.is_init_success - rospy.loginfo("success = {}".format(success)) if success: success &= example.home_the_robot() - except: + except Exception as e: + print (e) success = False # For testing purposes @@ -104,4 +107,5 @@ def main(): rospy.loginfo("The Gazebo initialization executed without fail.") if __name__ == '__main__': + rospy.init_node('init_robot') main() diff --git a/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/package.xml b/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/package.xml index 1e3add54..8e729e44 100644 --- a/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/package.xml +++ b/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/package.xml @@ -1,7 +1,7 @@ gen3_lite_gen3_lite_2f_move_it_config - 2.2.1 + 2.2.2 An automatically generated package with all the configuration and launch files for using the gen3_lite_gen3_lite_2f with the MoveIt! Motion Planning Framework diff --git a/kortex_move_it_config/gen3_move_it_config/package.xml b/kortex_move_it_config/gen3_move_it_config/package.xml index a409428c..f8040e4a 100644 --- a/kortex_move_it_config/gen3_move_it_config/package.xml +++ b/kortex_move_it_config/gen3_move_it_config/package.xml @@ -1,7 +1,7 @@ gen3_move_it_config - 2.2.1 + 2.2.2 An automatically generated package with all the configuration and launch files for using the gen3 with the MoveIt! Motion Planning Framework diff --git a/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/package.xml b/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/package.xml index bdd19f5f..50280983 100644 --- a/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/package.xml +++ b/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/package.xml @@ -1,7 +1,7 @@ gen3_robotiq_2f_140_move_it_config - 2.2.1 + 2.2.2 An automatically generated package with all the configuration and launch files for using the gen3_robotiq_2f_140 with the MoveIt! Motion Planning Framework diff --git a/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/package.xml b/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/package.xml index c5996940..1e215044 100644 --- a/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/package.xml +++ b/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/package.xml @@ -1,7 +1,7 @@ gen3_robotiq_2f_85_move_it_config - 2.2.1 + 2.2.2 An automatically generated package with all the configuration and launch files for using the gen3_robotiq_2f_85 with the MoveIt! Motion Planning Framework diff --git a/kortex_move_it_config/kortex_move_it_config/package.xml b/kortex_move_it_config/kortex_move_it_config/package.xml index 843b77b5..a9cbce90 100644 --- a/kortex_move_it_config/kortex_move_it_config/package.xml +++ b/kortex_move_it_config/kortex_move_it_config/package.xml @@ -1,12 +1,12 @@ kortex_move_it_config - 2.2.1 + 2.2.2 - The metapackage for the automatically generated MoveIt! configuration packages + The metapackage for the automatically generated MoveIt configuration packages Alexandre Vannobel - + BSD