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|