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

Implementation for angular position control, Cartesian position control and gripper position control #105

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
53 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
0a28790
Address PR comments
alexvannobel Jul 10, 2020
d271276
Fix tool frame for 6DOF Gen3 arm
alexvannobel Jul 10, 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
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ $(arg prefix)gen3_lite_2f_gripper_controller:

gazebo_ros_control:
pid_gains:
$(arg prefix)right_finger_bottom_joint: {p: 0.1, i: 0.0, d: 0.0}
$(arg prefix)right_finger_bottom_joint: {p: 10.0, i: 0.0, d: 0.0}
$(arg prefix)right_finger_tip_joint: {p: 1.0, i: 0.0, d: 0.0}
$(arg prefix)left_finger_bottom_joint: {p: 10.0, i: 0.0, d: 0.0}
$(arg prefix)left_finger_tip_joint: {p: 1.0, i: 0.0, d: 0.0}
14 changes: 14 additions & 0 deletions kortex_description/arms/gen3/6dof/config/joint_limits.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -5,3 +5,17 @@ joint_names:
- $(arg prefix)joint_4
- $(arg prefix)joint_5
- $(arg prefix)joint_6
maximum_velocities:
- 0.8727
- 0.8727
- 0.8727
- 0.8727
- 0.8727
- 0.8727
maximum_accelerations:
- 1.0
- 1.0
- 1.0
- 10.0
- 10.0
- 10.0
4 changes: 4 additions & 0 deletions kortex_description/arms/gen3/6dof/config/twist_limits.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
maximum_linear_velocity: 0.5
maximum_angular_velocity: 1.74
maximum_linear_acceleration: 0.4
maximum_angular_acceleration: 0.4
2 changes: 1 addition & 1 deletion kortex_description/arms/gen3/6dof/urdf/gen3_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -232,7 +232,7 @@
<joint
name="${prefix}end_effector"
type="fixed">
<origin xyz="0 0 -0.0615250000000001" rpy="3.14159265358979 1.09937075168372E-32 0" />
<origin xyz="0 0 -0.0615250000000001" rpy="3.14159265358979 1.09937075168372E-32 3.14159265358979" />
<parent
link="${prefix}bracelet_link" />
<child
Expand Down
18 changes: 17 additions & 1 deletion kortex_description/arms/gen3/7dof/config/joint_limits.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -5,4 +5,20 @@ joint_names:
- $(arg prefix)joint_4
- $(arg prefix)joint_5
- $(arg prefix)joint_6
- $(arg prefix)joint_7
- $(arg prefix)joint_7
maximum_velocities:
- 0.8727
- 0.8727
- 0.8727
- 0.8727
- 0.8727
- 0.8727
- 0.8727
maximum_accelerations:
- 1.0
- 1.0
- 1.0
- 1.0
- 10.0
- 10.0
- 10.0
4 changes: 4 additions & 0 deletions kortex_description/arms/gen3/7dof/config/twist_limits.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
maximum_linear_velocity: 0.5
maximum_angular_velocity: 1.74
maximum_linear_acceleration: 0.4
maximum_angular_acceleration: 0.4
14 changes: 14 additions & 0 deletions kortex_description/arms/gen3_lite/6dof/config/joint_limits.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -5,3 +5,17 @@ joint_names:
- $(arg prefix)joint_4
- $(arg prefix)joint_5
- $(arg prefix)joint_6
maximum_velocities:
- 0.5
- 0.5
- 0.5
- 0.5
- 0.5
- 0.5
maximum_accelerations:
- 1.0
- 0.5
- 0.4
- 1.0
- 10.0
- 10.0
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
maximum_linear_velocity: 0.3
maximum_angular_velocity: 0.85
maximum_linear_acceleration: 0.4
maximum_angular_acceleration: 0.4
Original file line number Diff line number Diff line change
Expand Up @@ -163,6 +163,7 @@ class KortexArmDriver
bool isGripperPresent();
void setAngularTrajectorySoftLimitsToMax();
void publishRobotFeedback();
void publishSimulationFeedback();
void registerSimulationHandlers();
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,15 +13,34 @@
*
*/

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

// MoveIt
#include <moveit/move_group_interface/move_group_interface.h>

// KDL
#include <kdl/chain.hpp>
#include <kdl/chainfksolverpos_recursive.hpp>
#include <kdl/chainiksolverpos_nr.hpp>
#include <kdl/chainiksolvervel_pinv.hpp>
#include <kdl/velocityprofile_trap.hpp>

// Standard
#include <unordered_map>
#include <thread>
#include <mutex>

// Kortex
#include "kortex_driver/non-generated/kortex_math_util.h"

#include "kortex_driver/ActionType.h"
#include "kortex_driver/KortexError.h"
#include "kortex_driver/BaseCyclic_Feedback.h"

#include "kortex_driver/CreateAction.h"
#include "kortex_driver/ReadAction.h"
Expand All @@ -43,8 +62,6 @@
#include "kortex_driver/SendGripperCommand.h"
#include "kortex_driver/ApplyEmergencyStop.h"

#include <moveit/move_group_interface/move_group_interface.h>

class KortexArmSimulation
{
public:
Expand All @@ -54,6 +71,8 @@ class KortexArmSimulation
std::unordered_map<uint32_t, kortex_driver::Action> GetActionsMap() const;
int GetDOF() const {return m_degrees_of_freedom;}

kortex_driver::BaseCyclic_Feedback GetFeedback();

// Handlers for simulated Kortex API functions
// Actions API
kortex_driver::CreateAction::Response CreateAction(const kortex_driver::CreateAction::Request& req);
Expand All @@ -74,31 +93,58 @@ class KortexArmSimulation
kortex_driver::ApplyEmergencyStop::Response ApplyEmergencyStop(const kortex_driver::ApplyEmergencyStop::Request& req);

private:

// ROS
ros::NodeHandle m_node_handle;

// Publishers
ros::Publisher m_pub_action_topic;

// Subscribers
ros::Subscriber m_sub_joint_trajectory_controller_state;
ros::Subscriber m_sub_joint_state;

// Action clients
std::unique_ptr<actionlib::SimpleActionClient<control_msgs::FollowJointTrajectoryAction>> m_follow_joint_trajectory_action_client;
std::unique_ptr<actionlib::SimpleActionClient<control_msgs::GripperCommandAction>> m_gripper_action_client;

// Namespacing and prefixing information
std::string m_prefix;
std::string m_robot_name;

// Arm and gripper information
// Arm information
std::string m_arm_name;
std::vector<std::string> m_arm_joint_names;
std::vector<float> m_arm_velocity_max_limits;
std::vector<float> m_arm_acceleration_max_limits;
float m_max_cartesian_twist_linear;
float m_max_cartesian_twist_angular;
float m_max_cartesian_acceleration_linear;
float m_max_cartesian_acceleration_angular;

// Gripper information
std::string m_gripper_name;
std::vector<std::string> m_gripper_joint_names;
std::vector<float> m_gripper_joint_limits_max;
std::vector<float> m_gripper_joint_limits_min;
int m_degrees_of_freedom;

// The indexes of the first arm joint and of the gripper joint in the "joint_states" feedback
int m_first_arm_joint_index;
int m_gripper_joint_index;

// Action-related
std::unordered_map<uint32_t, kortex_driver::Action> m_map_actions;

// Math utility
KortexMathUtil m_math_util;

// KDL chain, solvers and motions
KDL::Chain m_chain;
std::unique_ptr<KDL::ChainFkSolverPos_recursive> m_fk_solver;
std::unique_ptr<KDL::ChainIkSolverPos_NR> m_ik_pos_solver;
std::unique_ptr<KDL::ChainIkSolverVel_pinv> m_ik_vel_solver;
std::vector<KDL::VelocityProfile_Trap> m_velocity_trap_profiles;

// Threading
std::atomic<bool> m_is_action_being_executed;
std::atomic<bool> m_action_preempted;
Expand All @@ -108,12 +154,21 @@ class KortexArmSimulation
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;
kortex_driver::BaseCyclic_Feedback m_feedback;
std::mutex m_state_mutex;

// 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 CancelAction();
void JoinThreadAndCancelAction();
void PlayAction(const kortex_driver::Action& action);
kortex_driver::KortexError ExecuteReachJointAngles(const kortex_driver::Action& action);
kortex_driver::KortexError ExecuteReachPose(const kortex_driver::Action& action);
Expand Down
1 change: 1 addition & 0 deletions kortex_driver/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
<build_depend>control_msgs</build_depend>
<build_depend>actionlib</build_depend>
<build_depend>moveit_ros_planning_interface</build_depend>
<build_depend>kdl_parser</build_depend>
<build_export_depend>roscpp</build_export_depend>
<build_export_depend>rospy</build_export_depend>
<build_export_depend>std_msgs</build_export_depend>
Expand Down
14 changes: 14 additions & 0 deletions kortex_driver/src/non-generated/driver/kortex_arm_driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,10 @@ KortexArmDriver::KortexArmDriver(ros::NodeHandle nh): m_node_handle(nh),
{
m_publish_feedback_thread = std::thread(&KortexArmDriver::publishRobotFeedback, this);
}
else
{
m_publish_feedback_thread = std::thread(&KortexArmDriver::publishSimulationFeedback, this);
}

// If we get here and no error was thrown we started the node correctly
ROS_INFO("%sThe Kortex driver has been initialized correctly!%s", GREEN_COLOR_CONSOLE, RESET_COLOR_CONSOLE);
Expand Down Expand Up @@ -639,6 +643,16 @@ void KortexArmDriver::publishRobotFeedback()
}
}

void KortexArmDriver::publishSimulationFeedback()
{
ros::Rate rate(m_cyclic_data_publish_rate);
while (m_node_is_running)
{
m_pub_base_feedback.publish(m_simulator->GetFeedback());
rate.sleep();
}
}

void KortexArmDriver::registerSimulationHandlers()
{
BaseSimulationServices* base_services_simulation = dynamic_cast<BaseSimulationServices*>(m_base_ros_services);
Expand Down
Loading