-
Notifications
You must be signed in to change notification settings - Fork 155
/
kortex_arm_simulation.cpp
1676 lines (1502 loc) · 71 KB
/
kortex_arm_simulation.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/*
* KINOVA (R) KORTEX (TM)
*
* Copyright (c) 2020 Kinova inc. All rights reserved.
*
* This software may be modified and distributed under the
* terms of the BSD 3-Clause license.
*
* Refer to the LICENSE file for details.
*
*/
#include "kortex_driver/non-generated/kortex_arm_simulation.h"
#include "kortex_driver/ErrorCodes.h"
#include "kortex_driver/SubErrorCodes.h"
#include "kortex_driver/ActionNotification.h"
#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 <kdl_parser/kdl_parser.hpp>
#include <kdl/path_line.hpp>
#include <kdl/rotational_interpolation_sa.hpp>
#include <kdl/trajectory_segment.hpp>
#include <urdf/model.h>
#include <set>
#include <chrono>
#include <unordered_set>
namespace
{
static const std::string ARM_PLANNING_GROUP = "arm";
static const std::string GRIPPER_PLANNING_GROUP = "gripper";
static constexpr unsigned int FIRST_CREATED_ACTION_ID = 10000;
static const std::set<unsigned int> 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_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);
m_arm_joint_limits_min.resize(GetDOF());
m_arm_joint_limits_max.resize(GetDOF());
for (int i = 0; i < GetDOF(); i++)
{
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
ros::param::get("~maximum_linear_velocity", m_max_cartesian_twist_linear);
ros::param::get("~maximum_angular_velocity", m_max_cartesian_twist_angular);
ros::param::get("~maximum_linear_acceleration", m_max_cartesian_acceleration_linear);
ros::param::get("~maximum_angular_acceleration", m_max_cartesian_acceleration_angular);
// Gripper information
ros::param::get("~gripper", m_gripper_name);
if (IsGripperPresent())
{
ros::param::get("~gripper_joint_names", m_gripper_joint_names);
// The joint_states feedback uses alphabetical order for the indexes
// If the gripper joint is before
if (m_gripper_joint_names[0] < m_arm_joint_names[0])
{
m_gripper_joint_index = 0;
m_first_arm_joint_index = 1;
}
// If the gripper joint is after the arm joints
else
{
m_gripper_joint_index = GetDOF();
m_first_arm_joint_index = 0;
}
for (auto s : m_gripper_joint_names)
{
s.insert(0, m_prefix);
}
ros::param::get("~gripper_joint_limits_max", m_gripper_joint_limits_max);
ros::param::get("~gripper_joint_limits_min", m_gripper_joint_limits_min);
}
// Print out simulation configuration
ROS_INFO("Simulating arm with following characteristics:");
ROS_INFO("Arm type : %s", m_arm_name.c_str());
ROS_INFO("Gripper type : %s", m_gripper_name.empty() ? "None" : m_gripper_name.c_str());
ROS_INFO("Arm namespace : %s", m_robot_name.c_str());
ROS_INFO("URDF prefix : %s", m_prefix.c_str());
// Building the KDL chain from the robot description
// The chain goes from 'base_link' to 'tool_frame'
KDL::Tree tree;
if (!kdl_parser::treeFromParam("robot_description", tree))
{
const std::string error_string("Failed to parse robot_description parameter to build the kinematic tree!");
ROS_ERROR("%s", error_string.c_str());
throw(std::runtime_error(error_string));
}
if (!tree.getChain(m_prefix + "base_link", m_prefix + "tool_frame", m_chain))
{
const std::string error_string("Failed to extract kinematic chain from parsed tree!");
ROS_ERROR("%s", error_string.c_str());
throw(std::runtime_error(error_string));
}
m_fk_solver.reset(new KDL::ChainFkSolverPos_recursive(m_chain));
m_ik_vel_solver.reset(new KDL::ChainIkSolverVel_pinv(m_chain));
m_ik_pos_solver.reset(new KDL::ChainIkSolverPos_NR(m_chain, *m_fk_solver, *m_ik_vel_solver));
// Build the velocity profile for each joint using the max velocities and max accelerations
for (int i = 0; i < GetDOF(); i++)
{
m_velocity_trap_profiles.push_back(KDL::VelocityProfile_Trap(m_arm_velocity_max_limits[i], m_arm_acceleration_max_limits[i]));
}
// Start MoveIt client
m_moveit_arm_interface.reset(new moveit::planning_interface::MoveGroupInterface(ARM_PLANNING_GROUP));
if (IsGripperPresent())
{
m_moveit_gripper_interface.reset(new moveit::planning_interface::MoveGroupInterface(GRIPPER_PLANNING_GROUP));
}
// Create default actions
CreateDefaultActions();
// Create publishers and subscribers
for (int i = 0; i < GetDOF(); i++)
{
m_pub_position_controllers.push_back(m_node_handle.advertise<std_msgs::Float64>(
"/" + m_robot_name + "/" + m_prefix + "joint_" + std::to_string(i+1) + "_position_controller/command", 1000));
}
m_pub_action_topic = m_node_handle.advertise<kortex_driver::ActionNotification>("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<controller_manager_msgs::SwitchController>
("/" + 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<control_msgs::FollowJointTrajectoryAction>(
"/" + m_robot_name + "/" + m_prefix + m_arm_name + "_joint_trajectory_controller" + "/follow_joint_trajectory", true));
m_follow_joint_trajectory_action_client->waitForServer();
if (IsGripperPresent())
{
m_gripper_action_client.reset(new actionlib::SimpleActionClient<control_msgs::GripperCommandAction>(
"/" + m_robot_name + "/" + m_prefix + m_gripper_name + "_gripper_controller" + "/gripper_cmd", true));
m_gripper_action_client->waitForServer();
}
// Create usual ROS parameters
m_node_handle.setParam("degrees_of_freedom", m_degrees_of_freedom);
m_node_handle.setParam("is_gripper_present", IsGripperPresent());
m_node_handle.setParam("gripper_joint_names", m_gripper_joint_names);
m_node_handle.setParam("has_vision_module", false);
m_node_handle.setParam("has_interconnect_module", false);
}
KortexArmSimulation::~KortexArmSimulation()
{
JoinThreadAndCancelAction();
}
kortex_driver::BaseCyclic_Feedback KortexArmSimulation::GetFeedback()
{
// If the feedback is not yet received, return now
if (!m_first_state_received)
{
return m_feedback;
}
// Make a copy of current state
sensor_msgs::JointState current;
{
const std::lock_guard<std::mutex> lock(m_state_mutex);
current = m_current_state;
}
// Fill joint angles feedback
for (int i = 0; i < GetDOF(); i++)
{
m_feedback.actuators[i].position = m_math_util.wrapDegreesFromZeroTo360(m_math_util.toDeg(current.position[m_first_arm_joint_index + i]));
m_feedback.actuators[i].velocity = m_math_util.toDeg(current.velocity[m_first_arm_joint_index + i]);
}
// Calculate FK to get end effector pose
auto frame = KDL::Frame();
Eigen::VectorXd positions_eigen(GetDOF());
for (int i = 0; i < GetDOF(); i++)
{
positions_eigen[i] = current.position[m_first_arm_joint_index + i];
}
KDL::JntArray current_kdl(GetDOF());
current_kdl.data = positions_eigen;
m_fk_solver->JntToCart(current_kdl, frame);
m_feedback.base.tool_pose_x = frame.p.x();
m_feedback.base.commanded_tool_pose_x = frame.p.x();
m_feedback.base.tool_pose_y = frame.p.y();
m_feedback.base.commanded_tool_pose_y = frame.p.y();
m_feedback.base.tool_pose_z = frame.p.z();
m_feedback.base.commanded_tool_pose_z = frame.p.z();
double alpha, beta, gamma;
frame.M.GetEulerZYX(alpha, beta, gamma);
m_feedback.base.tool_pose_theta_x = m_math_util.toDeg(gamma);
m_feedback.base.commanded_tool_pose_theta_x = m_math_util.toDeg(gamma);
m_feedback.base.tool_pose_theta_y = m_math_util.toDeg(beta);
m_feedback.base.commanded_tool_pose_theta_y = m_math_util.toDeg(beta);
m_feedback.base.tool_pose_theta_z = m_math_util.toDeg(alpha);
m_feedback.base.commanded_tool_pose_theta_z = m_math_util.toDeg(alpha);
// Fill gripper information
if (IsGripperPresent())
{
// Gripper index is right after last actuator and is expressed in % in the base feedback (not in absolute position like in joint_states)
m_feedback.interconnect.oneof_tool_feedback.gripper_feedback[0].motor[0].position = 100.0 * m_math_util.relative_position_from_absolute(current.position[m_gripper_joint_index], m_gripper_joint_limits_min[0], m_gripper_joint_limits_max[0]);
}
return m_feedback;
}
kortex_driver::CreateAction::Response KortexArmSimulation::CreateAction(const kortex_driver::CreateAction::Request& req)
{
auto new_action = req.input;
unsigned int identifier = FIRST_CREATED_ACTION_ID;
bool identifier_taken = true;
// Find unique identifier for new action
while (identifier_taken)
{
identifier_taken = m_map_actions.count(identifier) == 1;
if (identifier_taken)
{
++identifier;
}
}
// Add Action to map if type is supported
switch (new_action.handle.action_type)
{
case kortex_driver::ActionType::REACH_JOINT_ANGLES:
case kortex_driver::ActionType::REACH_POSE:
case kortex_driver::ActionType::SEND_GRIPPER_COMMAND:
case kortex_driver::ActionType::TIME_DELAY:
new_action.handle.identifier = identifier;
new_action.handle.permission = 7;
m_map_actions.emplace(std::make_pair(identifier, new_action));
break;
default:
ROS_ERROR("Unsupported action type %d : could not create simulated action.", new_action.handle.action_type);
break;
}
// Return ActionHandle for added action
kortex_driver::CreateAction::Response response;
response.output = new_action.handle;
return response;
}
kortex_driver::ReadAction::Response KortexArmSimulation::ReadAction(const kortex_driver::ReadAction::Request& req)
{
auto input = req.input;
kortex_driver::ReadAction::Response response;
auto it = m_map_actions.find(input.identifier);
if (it != m_map_actions.end())
{
response.output = it->second;
}
return response;
}
kortex_driver::ReadAllActions::Response KortexArmSimulation::ReadAllActions(const kortex_driver::ReadAllActions::Request& req)
{
auto input = req.input;
kortex_driver::ReadAllActions::Response response;
kortex_driver::ActionList action_list;
for (auto a : m_map_actions)
{
// If requested action type is specified and matches iterated action's type, add it to the list
if (input.action_type == 0 || input.action_type == a.second.handle.action_type)
{
action_list.action_list.push_back(a.second);
}
}
response.output = action_list;
return response;
}
kortex_driver::DeleteAction::Response KortexArmSimulation::DeleteAction(const kortex_driver::DeleteAction::Request& req)
{
auto handle = req.input;
// If the action is not a default action
if (DEFAULT_ACTIONS_IDENTIFIERS.find(handle.identifier) == DEFAULT_ACTIONS_IDENTIFIERS.end())
{
auto it = m_map_actions.find(handle.identifier);
if (it != m_map_actions.end())
{
m_map_actions.erase(it);
ROS_INFO("Simulated action #%u properly deleted.", handle.identifier);
}
else
{
ROS_WARN("Could not find simulated action #%u to delete in actions map.", handle.identifier);
}
}
else
{
ROS_ERROR("Cannot delete default simulated actions.");
}
return kortex_driver::DeleteAction::Response();
}
kortex_driver::UpdateAction::Response KortexArmSimulation::UpdateAction(const kortex_driver::UpdateAction::Request& req)
{
auto action = req.input;
// If the action is not a default action
if (DEFAULT_ACTIONS_IDENTIFIERS.find(action.handle.identifier) == DEFAULT_ACTIONS_IDENTIFIERS.end())
{
auto it = m_map_actions.find(action.handle.identifier);
if (it != m_map_actions.end())
{
if (it->second.handle.action_type == action.handle.action_type)
{
it->second = action;
ROS_INFO("Simulated action #%u properly updated.", action.handle.identifier);
}
else
{
ROS_ERROR("Cannot update action with different type.");
}
}
else
{
ROS_ERROR("Could not find simulated action #%u to update in actions map.", action.handle.identifier);
}
}
else
{
ROS_ERROR("Cannot update default simulated actions.");
}
return kortex_driver::UpdateAction::Response();
}
kortex_driver::ExecuteActionFromReference::Response KortexArmSimulation::ExecuteActionFromReference(const kortex_driver::ExecuteActionFromReference::Request& req)
{
auto handle = req.input;
auto it = m_map_actions.find(handle.identifier);
if (it != m_map_actions.end())
{
JoinThreadAndCancelAction(); // this will block until the thread is joined and current action finished
m_action_executor_thread = std::thread(&KortexArmSimulation::PlayAction, this, it->second);
}
else
{
ROS_ERROR("Could not find action with given identifier %d", handle.identifier);
}
return kortex_driver::ExecuteActionFromReference::Response();
}
kortex_driver::ExecuteAction::Response KortexArmSimulation::ExecuteAction(const kortex_driver::ExecuteAction::Request& req)
{
auto action = req.input;
// Add Action to map if type is supported
switch (action.handle.action_type)
{
case kortex_driver::ActionType::REACH_JOINT_ANGLES:
case kortex_driver::ActionType::REACH_POSE:
case kortex_driver::ActionType::SEND_GRIPPER_COMMAND:
case kortex_driver::ActionType::TIME_DELAY:
JoinThreadAndCancelAction(); // this will block until the thread is joined and current action finished
m_action_executor_thread = std::thread(&KortexArmSimulation::PlayAction, this, action);
break;
default:
ROS_ERROR("Unsupported action type %d : could not execute simulated action.", action.handle.action_type);
break;
}
return kortex_driver::ExecuteAction::Response();
}
kortex_driver::StopAction::Response KortexArmSimulation::StopAction(const kortex_driver::StopAction::Request& req)
{
if (m_is_action_being_executed.load())
{
JoinThreadAndCancelAction(); // this will block until the thread is joined and current action finished
}
m_follow_joint_trajectory_action_client->cancelAllGoals();
if (IsGripperPresent())
{
m_gripper_action_client->cancelAllGoals();
}
return kortex_driver::StopAction::Response();
}
kortex_driver::PlayCartesianTrajectory::Response KortexArmSimulation::PlayCartesianTrajectory(const kortex_driver::PlayCartesianTrajectory::Request& req)
{
auto constrained_pose = req.input;
kortex_driver::Action action;
action.name = "PlayCartesianTrajectory";
action.handle.action_type = kortex_driver::ActionType::REACH_POSE;
action.oneof_action_parameters.reach_pose.push_back(constrained_pose);
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::PlayCartesianTrajectory::Response();
}
kortex_driver::SendTwistCommand::Response KortexArmSimulation::SendTwistCommand(const kortex_driver::SendTwistCommand::Request& req)
{
auto twist_command = req.input;
kortex_driver::Action action;
action.name = "SendTwistCommand";
action.handle.action_type = kortex_driver::ActionType::SEND_TWIST_COMMAND;
action.oneof_action_parameters.send_twist_command.push_back(twist_command);
// 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();
}
kortex_driver::PlayJointTrajectory::Response KortexArmSimulation::PlayJointTrajectory(const kortex_driver::PlayJointTrajectory::Request& req)
{
auto constrained_joint_angles = req.input;
kortex_driver::Action action;
action.name = "PlayJointTrajectory";
action.handle.action_type = kortex_driver::ActionType::REACH_JOINT_ANGLES;
action.oneof_action_parameters.reach_joint_angles.push_back(constrained_joint_angles);
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::PlayJointTrajectory::Response();
}
kortex_driver::SendJointSpeedsCommand::Response KortexArmSimulation::SendJointSpeedsCommand(const kortex_driver::SendJointSpeedsCommand::Request& req)
{
auto joint_speeds = req.input;
kortex_driver::Action action;
action.name = "SendJointSpeedsCommand";
action.handle.action_type = kortex_driver::ActionType::SEND_JOINT_SPEEDS;
action.oneof_action_parameters.send_joint_speeds.push_back(joint_speeds);
// 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();
}
kortex_driver::SendGripperCommand::Response KortexArmSimulation::SendGripperCommand(const kortex_driver::SendGripperCommand::Request& req)
{
auto gripper_command = req.input;
kortex_driver::Action action;
action.name = "GripperCommand";
action.handle.action_type = kortex_driver::ActionType::SEND_GRIPPER_COMMAND;
action.oneof_action_parameters.send_gripper_command.push_back(gripper_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::SendGripperCommand::Response();
}
kortex_driver::Stop::Response KortexArmSimulation::Stop(const kortex_driver::Stop::Request& req)
{
// If an action is ongoing, cancel it first
if (m_is_action_being_executed.load())
{
JoinThreadAndCancelAction(); // this will block until the thread is joined and current action finished
}
m_follow_joint_trajectory_action_client->cancelAllGoals();
if (IsGripperPresent())
{
m_gripper_action_client->cancelAllGoals();
}
return kortex_driver::Stop::Response();
}
kortex_driver::ApplyEmergencyStop::Response KortexArmSimulation::ApplyEmergencyStop(const kortex_driver::ApplyEmergencyStop::Request& req)
{
// If an action is ongoing, cancel it first
if (m_is_action_being_executed.load())
{
JoinThreadAndCancelAction(); // this will block until the thread is joined and current action finished
}
m_follow_joint_trajectory_action_client->cancelAllGoals();
if (IsGripperPresent())
{
m_gripper_action_client->cancelAllGoals();
}
return kortex_driver::ApplyEmergencyStop::Response();
}
void KortexArmSimulation::cb_joint_states(const sensor_msgs::JointState& state)
{
const std::lock_guard<std::mutex> lock(m_state_mutex);
m_first_state_received = true;
m_current_state = state;
}
void KortexArmSimulation::CreateDefaultActions()
{
kortex_driver::Action retract, home, zero;
kortex_driver::ConstrainedJointAngles retract_angles, home_angles, zero_angles;
// Retract
retract.handle.identifier = 1;
retract.handle.action_type = kortex_driver::ActionType::REACH_JOINT_ANGLES;
retract.handle.permission = 7;
retract.name = "Retract";
for (int i = 0; i < m_degrees_of_freedom; i++)
{
kortex_driver::JointAngle a;
a.joint_identifier = i;
auto named_target = m_moveit_arm_interface->getNamedTargetValues("retract");
double moveit_angle = named_target[m_prefix + "joint_"+std::to_string(i+1)]; // rad
a.value = m_math_util.wrapDegreesFromZeroTo360(m_math_util.toDeg(moveit_angle));
retract_angles.joint_angles.joint_angles.push_back(a);
}
retract.oneof_action_parameters.reach_joint_angles.push_back(retract_angles);
// Home
home.handle.identifier = 2;
home.handle.action_type = kortex_driver::ActionType::REACH_JOINT_ANGLES;
home.handle.permission = 7;
home.name = "Home";
for (int i = 0; i < m_degrees_of_freedom; i++)
{
kortex_driver::JointAngle a;
a.joint_identifier = i;
auto named_target = m_moveit_arm_interface->getNamedTargetValues("home");
double moveit_angle = named_target[m_prefix + "joint_"+std::to_string(i+1)]; // rad
a.value = m_math_util.wrapDegreesFromZeroTo360(m_math_util.toDeg(moveit_angle));
home_angles.joint_angles.joint_angles.push_back(a);
}
home.oneof_action_parameters.reach_joint_angles.push_back(home_angles);
// Zero
zero.handle.identifier = 3;
zero.handle.action_type = kortex_driver::ActionType::REACH_JOINT_ANGLES;
zero.handle.permission = 7;
zero.name = "Zero";
for (int i = 0; i < m_degrees_of_freedom; i++)
{
kortex_driver::JointAngle a;
a.joint_identifier = i;
auto named_target = m_moveit_arm_interface->getNamedTargetValues("vertical");
double moveit_angle = named_target[m_prefix + "joint_"+std::to_string(i+1)]; // rad
a.value = m_math_util.wrapDegreesFromZeroTo360(m_math_util.toDeg(moveit_angle));
zero_angles.joint_angles.joint_angles.push_back(a);
}
zero.oneof_action_parameters.reach_joint_angles.push_back(zero_angles);
// Add actions
m_map_actions.emplace(std::make_pair(retract.handle.identifier, retract));
m_map_actions.emplace(std::make_pair(home.handle.identifier, home));
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;
error.code = code;
error.subCode = subCode;
error.description = description;
return error;
}
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;
}
void KortexArmSimulation::PlayAction(const kortex_driver::Action& action)
{
auto action_result = FillKortexError(kortex_driver::ErrorCodes::ERROR_NONE, kortex_driver::SubErrorCodes::SUB_ERROR_NONE);
// Notify action started
kortex_driver::ActionNotification start_notif;
start_notif.handle = action.handle;
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)
{
case kortex_driver::ActionType::REACH_JOINT_ANGLES:
action_result = ExecuteReachJointAngles(action);
break;
case kortex_driver::ActionType::REACH_POSE:
action_result = ExecuteReachPose(action);
break;
case kortex_driver::ActionType::SEND_JOINT_SPEEDS:
action_result = ExecuteSendJointSpeeds(action);
break;
case kortex_driver::ActionType::SEND_TWIST_COMMAND:
action_result = ExecuteSendTwist(action);
break;
case kortex_driver::ActionType::SEND_GRIPPER_COMMAND:
action_result = ExecuteSendGripperCommand(action);
break;
case kortex_driver::ActionType::TIME_DELAY:
action_result = ExecuteTimeDelay(action);
break;
default:
action_result = FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE, kortex_driver::SubErrorCodes::UNSUPPORTED_ACTION);
break;
}
// Oddly enough, gripper actions don't send notifications through Kortex API when they end
if (action.handle.action_type != kortex_driver::ActionType::SEND_GRIPPER_COMMAND)
{
kortex_driver::ActionNotification end_notif;
end_notif.handle = action.handle;
// 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;
ROS_WARN("Action was aborted by user.");
}
// Action ended on its own
else
{
if (action_result.code != kortex_driver::ErrorCodes::ERROR_NONE)
{
// Notify ACTION_ABORT
end_notif.action_event = kortex_driver::ActionEvent::ACTION_ABORT;
end_notif.abort_details = action_result.subCode;
ROS_WARN("Action was failed : \nError code is %d\nSub-error code is %d\nError description is : %s",
action_result.code,
action_result.subCode,
action_result.description.c_str());
}
else
{
// Notify ACTION_END
end_notif.action_event = kortex_driver::ActionEvent::ACTION_END;
}
}
m_pub_action_topic.publish(end_notif);
}
m_is_action_being_executed = false;
}
kortex_driver::KortexError KortexArmSimulation::ExecuteReachJointAngles(const kortex_driver::Action& action)
{
auto result = FillKortexError(kortex_driver::ErrorCodes::ERROR_NONE, kortex_driver::SubErrorCodes::SUB_ERROR_NONE);
if (action.oneof_action_parameters.reach_joint_angles.size() != 1)
{
return FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE,
kortex_driver::SubErrorCodes::INVALID_PARAM,
"Error playing joint angles action : action is malformed.");
}
auto constrained_joint_angles = action.oneof_action_parameters.reach_joint_angles[0];
if (constrained_joint_angles.joint_angles.joint_angles.size() != GetDOF())
{
return FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE,
kortex_driver::SubErrorCodes::INVALID_PARAM,
"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";
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
traj.joint_names.push_back(joint_name);
}
// Get current position
sensor_msgs::JointState current;
{
const std::lock_guard<std::mutex> lock(m_state_mutex);
current = m_current_state;
}
// Transform kortex structure to trajectory_msgs to fill endpoint structure
trajectory_msgs::JointTrajectoryPoint endpoint;
std::unordered_set<int> limited_joints; // joints limited in range
int degrees_of_freedom = constrained_joint_angles.joint_angles.joint_angles.size();
if (degrees_of_freedom == 6)
{
limited_joints = {1,2,4};
}
else if (degrees_of_freedom == 7)
{
limited_joints = {1,3,5};
}
else
{
return FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE,
kortex_driver::SubErrorCodes::INVALID_PARAM,
"Unsupported number of joints, expected 6 or 7");
}
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;
double rad_wrapped_goal;
if (limited_joints.count(i))
{
rad_wrapped_goal = m_math_util.wrapRadiansFromMinusPiToPi(m_math_util.toRad(constrained_joint_angles.joint_angles.joint_angles[i].value));
}
else
{
rad_wrapped_goal = m_math_util.wrapRadiansFromMinusPiToPi(m_math_util.toRad(constrained_joint_angles.joint_angles.joint_angles[i].value), n_turns);
}
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);
}
// Calculate velocity profiles to know how much time this trajectory must last
switch (constrained_joint_angles.constraint.type)
{
// If the duration is supplied, set the duration of the velocity profiles with that value
case kortex_driver::JointTrajectoryConstraintType::JOINT_CONSTRAINT_DURATION:
{
// Error check on the given duration
if (constrained_joint_angles.constraint.value <= 0.0f)
{
return FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE,
kortex_driver::SubErrorCodes::INVALID_PARAM,
"Invalid duration constraint : it has to be higher than 0.0!");
}
// Set the velocity profiles
for (int i = 0; i < GetDOF(); i++)
{
m_velocity_trap_profiles[i].SetProfileDuration(current.position[m_first_arm_joint_index + i], endpoint.positions[i], constrained_joint_angles.constraint.value);
}
endpoint.time_from_start = ros::Duration(constrained_joint_angles.constraint.value);
ROS_DEBUG("Using supplied duration : %2.2f", constrained_joint_angles.constraint.value);
break;
}
// If a max velocity is supplied for each joint, we need to find the limiting duration with this velocity constraint
case kortex_driver::JointTrajectoryConstraintType::JOINT_CONSTRAINT_SPEED:
{
// Error check on the given velocity
float max_velocity = m_math_util.toRad(constrained_joint_angles.constraint.value);
if (max_velocity <= 0.0f)
{
return FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE,
kortex_driver::SubErrorCodes::INVALID_PARAM,
"Invalid velocity constraint : it has to be higher than 0.0!");
}
// Find the limiting duration with given velocity
double max_duration = 0.0;
for (int i = 0; i < GetDOF(); i++)
{
double velocity_ratio = std::min(1.0, double(max_velocity)/m_arm_velocity_max_limits[i]);
m_velocity_trap_profiles[i].SetProfileVelocity(current.position[m_first_arm_joint_index + i], endpoint.positions[i], velocity_ratio);
max_duration = std::max(max_duration, m_velocity_trap_profiles[i].Duration());
ROS_DEBUG("Joint %d moving from %2.2f to %2.2f gives duration %2.2f", i, current.position[m_first_arm_joint_index + i], endpoint.positions[i], m_velocity_trap_profiles[i].Duration());
}
ROS_DEBUG("max_duration is : %2.2f", max_duration);
// Set the velocity profiles
for (int i = 0; i < GetDOF(); i++)
{
m_velocity_trap_profiles[i].SetProfileDuration(current.position[m_first_arm_joint_index + i], endpoint.positions[i], max_duration);
}
endpoint.time_from_start = ros::Duration(max_duration);
break;
}
default:
{
// Find the optimal duration based on actual velocity and acceleration limits
double optimal_duration = 0.0;
for (int i = 0; i < GetDOF(); i++)
{
m_velocity_trap_profiles[i].SetProfile(current.position[m_first_arm_joint_index + i], endpoint.positions[i]);
optimal_duration = std::max(optimal_duration, m_velocity_trap_profiles[i].Duration());
ROS_DEBUG("Joint %d moving from %2.2f to %2.2f gives duration %2.2f", i, current.position[m_first_arm_joint_index + i], endpoint.positions[i], m_velocity_trap_profiles[i].Duration());
}
ROS_DEBUG("optimal_duration is : %2.2f", optimal_duration);
// Set the velocity profiles
for (int i = 0; i < GetDOF(); i++)
{
m_velocity_trap_profiles[i].SetProfileDuration(current.position[m_first_arm_joint_index + i], endpoint.positions[i], optimal_duration);
}
endpoint.time_from_start = ros::Duration(optimal_duration);
break;
}
}
// Copy velocity profile data into trajectory using JOINT_TRAJECTORY_TIMESTEP_SECONDS timesteps
// For each timestep
for (double t = JOINT_TRAJECTORY_TIMESTEP_SECONDS; t < m_velocity_trap_profiles[0].Duration(); t += JOINT_TRAJECTORY_TIMESTEP_SECONDS)
{
// Create trajectory point
trajectory_msgs::JointTrajectoryPoint p;
p.time_from_start = ros::Duration(t);
// Add position, velocity, acceleration from each velocity profile
for (int i = 0; i < GetDOF(); i++)
{
p.positions.push_back(m_velocity_trap_profiles[i].Pos(t));
p.velocities.push_back(m_velocity_trap_profiles[i].Vel(t));
p.accelerations.push_back(m_velocity_trap_profiles[i].Acc(t));
}
// Add trajectory point to goal
traj.points.push_back(p);
}
// Finally, add endpoint to trajectory
// Add position, velocity, acceleration from each velocity profile
trajectory_msgs::JointTrajectoryPoint p;
p.time_from_start = ros::Duration(m_velocity_trap_profiles[0].Duration());
for (int i = 0; i < GetDOF(); i++)
{
p.positions.push_back(m_velocity_trap_profiles[i].Pos(m_velocity_trap_profiles[i].Duration()));
p.velocities.push_back(m_velocity_trap_profiles[i].Vel(m_velocity_trap_profiles[i].Duration()));
p.accelerations.push_back(m_velocity_trap_profiles[i].Acc(m_velocity_trap_profiles[i].Duration()));
}
// Add trajectory point to goal
traj.points.push_back(p);
// Verify if goal has been cancelled before sending it
if (m_action_preempted.load())
{
return result;
}
// 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 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())
{
m_follow_joint_trajectory_action_client->cancelAllGoals();
}
// Fill result depending on action final status if user didn't cancel
else
{
auto status = m_follow_joint_trajectory_action_client->getResult();
if (status->error_code != status->SUCCESSFUL)
{
result = FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE,
kortex_driver::SubErrorCodes::INVALID_PARAM,
status->error_string);
}