Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Velocity control, documentation and examples update #109

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
62 commits
Select commit Hold shift + click to select a range
7f5f14c
Created interface class and put the RPC handlers in robot folder
alexvannobel Jun 9, 2020
8fe70f3
Now the robot functions interface work just like before
alexvannobel Jun 9, 2020
e0d02d3
Added templates and generation for simulated services
alexvannobel Jun 9, 2020
6637d45
Added the simulation services to the driver headers
alexvannobel Jun 9, 2020
892513b
Added newly generated files to repo
alexvannobel Jun 9, 2020
382909f
Added simulation option to the driver so the gazebo package can launc…
alexvannobel Jun 10, 2020
4e44824
Adapt joint_limits files to correctly take prefix option
alexvannobel Jun 10, 2020
0e6cfe6
Change description and control files to support prefix option
alexvannobel Jun 10, 2020
9de4f6c
Change MoveIt config launch and config files to enable prefix option …
alexvannobel Jun 10, 2020
ab82fde
Added xacro usage in SRDF files to be able to prefix joint names
alexvannobel Jun 10, 2020
3c01900
Adjust ompl planning launch and config files to support prefixing joi…
alexvannobel Jun 11, 2020
f22a40d
Remove --inorder from xacro calls since it's default now
alexvannobel Jun 11, 2020
edec94a
Merge branch 'feature/improve-simulation' into feature/adapt-simulati…
alexvannobel Jun 11, 2020
5587eea
Set default gripper in launch files
alexvannobel Jun 11, 2020
d1990b5
Add namespace to launch file parameters passed to driver
alexvannobel Jun 11, 2020
6b86feb
Added class and implementation for simulator
alexvannobel Jun 11, 2020
fd2c4f3
Add stubs and register handlers for Action API
alexvannobel Jun 11, 2020
4e66bc9
Add implementation for default actions and ReacAction/ReadAllActions
alexvannobel Jun 15, 2020
088919e
Added some unit tests for simulator and CreateAction implentation
alexvannobel Jun 15, 2020
f9abad1
Added the case where the prefix could be empty in XACRO
alexvannobel Jun 15, 2020
efcf923
Added prefix support for fake controllers in MoveIt configs
alexvannobel Jun 15, 2020
6f5b45b
Added a missing prefix value for Gen3 and fix the if and unless tags
alexvannobel Jun 15, 2020
19811b5
Add test launch file to launch simulator unit tests
alexvannobel Jun 15, 2020
1d24817
Don't create the gripper Move Group if no gripper on the arm
alexvannobel Jun 15, 2020
e2843c0
Added DeleteAction implementation and tests
alexvannobel Jun 15, 2020
634e36b
Add implementation and tests for UpdateAction
alexvannobel Jun 16, 2020
b7be7b7
Added basic frame for a threaded action executor
alexvannobel Jun 16, 2020
c5d5785
Added publishing for action topic before and after action execution
alexvannobel Jun 16, 2020
798b43c
Added StopAction logic and tests for executing and aborting actions
alexvannobel Jun 16, 2020
45ae121
Added stubs for other RPCs we want to support at first in simulation
alexvannobel Jun 16, 2020
3f33b02
Added implementation for other RPCs worth simulating
alexvannobel Jun 16, 2020
6fd9104
Added some data structure checks and TODOs in executors
alexvannobel Jun 16, 2020
a78256f
Added tests for newly added RPCs
alexvannobel Jun 16, 2020
6a1b08f
Merge branch 'feature/improve-simulation' into feature/create-simulat…
alexvannobel Jun 16, 2020
e490b55
Remove merge artefacts
alexvannobel Jun 17, 2020
aa73b35
Added implementation for ReachJointAngles action - optimal duration i…
alexvannobel Jun 17, 2020
8323bb7
Added KDL parsing and solvers construction
alexvannobel Jun 18, 2020
ef124ae
Add max velocities and max accelerations to joint_limits.yaml files
alexvannobel Jun 18, 2020
bc4d256
Add a helper to fill KortexError and finish velocity profiles impleme…
alexvannobel Jun 18, 2020
d01460e
Now use the velocity profile data to fill the trajectory
alexvannobel Jun 18, 2020
4b1a1e9
Add implementation for angular position control
alexvannobel Jun 22, 2020
139ccc6
Merge branch 'feature/improve-simulation' into feature/angular-contro…
alexvannobel Jun 22, 2020
6b8a809
Add same ROS parameters than real arm and adjust first timestamp to n…
alexvannobel Jun 22, 2020
6931bfe
Fix MoveIt config Gen3 lite home position
alexvannobel Jun 23, 2020
b1291b5
Added ReachPose implementation, twist limits still hardcoded
alexvannobel Jun 30, 2020
327bc02
Add twist limits files for simulation
alexvannobel Jun 30, 2020
3231fea
Use the correct Cartesian velocity and acceleration values for each a…
alexvannobel Jun 30, 2020
c2bbd70
Add simulated feedback support and change current state to fetch join…
alexvannobel Jun 30, 2020
13144a2
Added implementation for gripper control
alexvannobel Jun 30, 2020
26a9581
Fixed a Robotiq 2F-140 typo in the moveit config
alexvannobel Jul 1, 2020
ad3c266
Added indexes for first arm joint and gripper joint because sometimes…
alexvannobel Jul 1, 2020
ccc5444
Changed the way the individual position controllers are loaded and st…
alexvannobel Jul 2, 2020
dfbd99d
Added implementation for angular velocity control and added joint lim…
alexvannobel Jul 2, 2020
ea0b760
Added wrapping around in reach joint angles
alexvannobel Jul 6, 2020
6227150
Fix a problem with timestamps
alexvannobel Jul 6, 2020
86ece71
Added an implementation for SendTwistCommand but not stable enough to…
alexvannobel Jul 10, 2020
0180188
Merge branch 'feature/improve-simulation' into feature/angular-veloci…
alexvannobel Jul 10, 2020
e45a1e2
Dont start the joint_7 controller for a 6DOF robot
alexvannobel Jul 13, 2020
789c991
Changed the examples to use notifications to check whether an action …
alexvannobel Jul 13, 2020
cb262d2
Put back the homing script for Gazebo and removed the copyright notic…
alexvannobel Jul 13, 2020
6940cc8
Adapt documentation for new simulation features
alexvannobel Jul 14, 2020
2032ec8
Updated the package.xml's with bumped versions and author and maintai…
alexvannobel Jul 14, 2020
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 4 additions & 4 deletions kortex_control/package.xml
Original file line number Diff line number Diff line change
@@ -1,12 +1,12 @@
<package>
<name>kortex_control</name>
<version>2.2.0</version>
<version>2.2.2</version>
<description>
<p>Gazebo Ros Control package for Kortex robots</p>
<p>This package contains launch and configuration files for the ros_control controllers for simulation</p>
<p>Gazebo ROS Control package for simulated Kortex robots</p>
<p>This package contains configuration files for the gazebo_ros_control controllers for simulation of Kortex arms</p>
</description>
<author email="[email protected]">Alexandre Vannobel</author>
<maintainer email="support@kinova.ca" />
<maintainer email="avannobel@kinova.ca" />
<license>BSD</license>
<buildtool_depend>catkin</buildtool_depend>
<build_depend>roslaunch</build_depend>
Expand Down
9 changes: 5 additions & 4 deletions kortex_description/package.xml
Original file line number Diff line number Diff line change
@@ -1,12 +1,13 @@
<package>
<name>kortex_description</name>
<version>2.2.1</version>
<version>2.2.2</version>
<description>
<p>URDF Description package for Kortex-compatible robots</p>
<p>URDF and xacro description package for Kortex robots</p>
<p>This package contains configuration data, 3D models and launch files
for Kortex-compatible arms and grippers</p>
for Kortex arms and supported grippers</p>
</description>
<maintainer email="[email protected]" />
<author email="[email protected]">Alexandre Vannobel</author>
<maintainer email="[email protected]" />
<license>BSD</license>
<buildtool_depend>catkin</buildtool_depend>
<build_depend>roslaunch</build_depend>
Expand Down
2 changes: 1 addition & 1 deletion kortex_driver/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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")
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,11 @@

// ROS
#include <ros/ros.h>
#include <std_msgs/Empty.h>
#include <control_msgs/JointTrajectoryControllerState.h>
#include <control_msgs/FollowJointTrajectoryAction.h>
#include <control_msgs/GripperCommandAction.h>
#include <actionlib/client/simple_action_client.h>
#include <actionlib/client/action_client.h>

// MoveIt
#include <moveit/move_group_interface/move_group_interface.h>
Expand Down Expand Up @@ -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:
Expand Down Expand Up @@ -98,10 +105,24 @@ class KortexArmSimulation

// Publishers
ros::Publisher m_pub_action_topic;
std::vector<ros::Publisher> 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<std::string> m_trajectory_controllers_list;
std::vector<std::string> m_position_controllers_list;
std::vector<double> m_velocity_commands;
kortex_driver::Twist m_twist_command;

// Action clients
std::unique_ptr<actionlib::SimpleActionClient<control_msgs::FollowJointTrajectoryAction>> m_follow_joint_trajectory_action_client;
Expand All @@ -114,6 +135,8 @@ class KortexArmSimulation
// Arm information
std::string m_arm_name;
std::vector<std::string> m_arm_joint_names;
std::vector<double> m_arm_joint_limits_min;
std::vector<double> m_arm_joint_limits_max;
std::vector<float> m_arm_velocity_max_limits;
std::vector<float> m_arm_acceleration_max_limits;
float m_max_cartesian_twist_linear;
Expand Down Expand Up @@ -148,14 +171,14 @@ class KortexArmSimulation
// Threading
std::atomic<bool> m_is_action_being_executed;
std::atomic<bool> m_action_preempted;
std::atomic<int> m_current_action_type;
std::thread m_action_executor_thread;

// MoveIt-related
std::unique_ptr<moveit::planning_interface::MoveGroupInterface> m_moveit_arm_interface;
std::unique_ptr<moveit::planning_interface::MoveGroupInterface> 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;
Expand All @@ -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_
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
*/

#include <cmath>
#include "kortex_driver/Twist.h"

class KortexMathUtil
{
Expand All @@ -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
9 changes: 6 additions & 3 deletions kortex_driver/package.xml
Original file line number Diff line number Diff line change
@@ -1,10 +1,12 @@
<?xml version="1.0"?>
<package format="2">
<name>kortex_driver</name>
<version>2.2.1</version>
<description>THe kortex package that act as a robot's driver.</description>
<version>2.2.2</version>
<description>The package that acts as a robot's driver. Supports simulated and real Kortex robots.</description>

<maintainer email="[email protected]" />
<author email="[email protected]">Hugo Lamontagne</author>
<author email="[email protected]">Alexandre Vannobel</author>
<maintainer email="[email protected]" />

<license>BSD</license>

Expand All @@ -13,6 +15,7 @@
<build_depend>rospy</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>control_msgs</build_depend>
<build_depend>controller_manager_msgs</build_depend>
<build_depend>actionlib</build_depend>
<build_depend>moveit_ros_planning_interface</build_depend>
<build_depend>kdl_parser</build_depend>
Expand Down
2 changes: 1 addition & 1 deletion kortex_driver/readme.md
Original file line number Diff line number Diff line change
Expand Up @@ -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**.
Expand Down
4 changes: 3 additions & 1 deletion kortex_driver/src/non-generated/driver/kortex_arm_driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Loading