Skip to content

Commit f021809

Browse files
authored
Merge release 2.3 to kinetic-devel (Kinovarobotics#154)
* Update driver for release 2.3 * Update examples for release 2.3 * Update MoveIt config files for release 2.3 * Update readme
1 parent 996ffaf commit f021809

File tree

132 files changed

+3298
-635
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

132 files changed

+3298
-635
lines changed

kortex_driver/CMakeLists.txt

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -54,11 +54,13 @@ foreach(sub_dir ${srv_generated_dir_list})
5454
add_service_files(DIRECTORY srv/generated/${sub_dir})
5555
endforeach()
5656

57+
add_action_files(DIRECTORY action/non_generated)
58+
5759
## generate added messages and services
58-
generate_messages(DEPENDENCIES std_msgs)
60+
generate_messages(DEPENDENCIES std_msgs actionlib_msgs)
5961

6062
## declare a catkin package
61-
catkin_package()
63+
catkin_package(CATKIN_DEPENDS actionlib_msgs)
6264

6365
if(USE_CONAN)
6466
# Include conan.cmake module and download Kortex API from artifactory
Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,15 @@
1+
#The trajectory to follow
2+
CartesianWaypoint[] trajectory
3+
duration goal_time_tolerance
4+
bool use_optimal_blending
5+
---
6+
#result definition
7+
string error_string
8+
int32 error_code
9+
int32 SUCCESSFUL = 0
10+
int32 INVALID_GOAL = -1
11+
int32 PATH_TOLERANCE_VIOLATED = -2
12+
13+
---
14+
#feedback
15+
CartesianWaypoint actual

kortex_driver/conanfile.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -6,4 +6,4 @@
66
class ROSKortexConan(ConanFile):
77

88
def requirements(self):
9-
self.requires("kortex_api_cpp/2.2.0-r.31@kortex/stable")
9+
self.requires("kortex_api_cpp/2.3.0-r.34@kortex/stable")

kortex_driver/include/kortex_driver/generated/interfaces/base_services_interface.h

Lines changed: 16 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -84,8 +84,8 @@
8484
#include "kortex_driver/ConfigurationChangeNotification.h"
8585
#include "kortex_driver/OnNotificationMappingInfoTopic.h"
8686
#include "kortex_driver/MappingInfoNotification.h"
87-
#include "kortex_driver/OnNotificationControlModeTopic.h"
88-
#include "kortex_driver/ControlModeNotification.h"
87+
#include "kortex_driver/Base_OnNotificationControlModeTopic.h"
88+
#include "kortex_driver/Base_ControlModeNotification.h"
8989
#include "kortex_driver/OnNotificationOperatingModeTopic.h"
9090
#include "kortex_driver/OperatingModeNotification.h"
9191
#include "kortex_driver/OnNotificationSequenceInfoTopic.h"
@@ -176,12 +176,16 @@
176176
#include "kortex_driver/DeleteAllSequenceTasks.h"
177177
#include "kortex_driver/TakeSnapshot.h"
178178
#include "kortex_driver/GetFirmwareBundleVersions.h"
179+
#include "kortex_driver/ExecuteWaypointTrajectory.h"
179180
#include "kortex_driver/MoveSequenceTask.h"
180181
#include "kortex_driver/DuplicateMapping.h"
181182
#include "kortex_driver/DuplicateMap.h"
182183
#include "kortex_driver/SetControllerConfiguration.h"
183184
#include "kortex_driver/GetControllerConfiguration.h"
184185
#include "kortex_driver/GetAllControllerConfigurations.h"
186+
#include "kortex_driver/ComputeForwardKinematics.h"
187+
#include "kortex_driver/ComputeInverseKinematics.h"
188+
#include "kortex_driver/ValidateWaypointList.h"
185189

186190
#include "kortex_driver/KortexError.h"
187191
#include "kortex_driver/SetDeviceID.h"
@@ -257,7 +261,7 @@ class IBaseServices
257261
virtual void cb_ConfigurationChangeTopic(Kinova::Api::Base::ConfigurationChangeNotification notif) = 0;
258262
virtual bool OnNotificationMappingInfoTopic(kortex_driver::OnNotificationMappingInfoTopic::Request &req, kortex_driver::OnNotificationMappingInfoTopic::Response &res) = 0;
259263
virtual void cb_MappingInfoTopic(Kinova::Api::Base::MappingInfoNotification notif) = 0;
260-
virtual bool OnNotificationControlModeTopic(kortex_driver::OnNotificationControlModeTopic::Request &req, kortex_driver::OnNotificationControlModeTopic::Response &res) = 0;
264+
virtual bool Base_OnNotificationControlModeTopic(kortex_driver::Base_OnNotificationControlModeTopic::Request &req, kortex_driver::Base_OnNotificationControlModeTopic::Response &res) = 0;
261265
virtual void cb_ControlModeTopic(Kinova::Api::Base::ControlModeNotification notif) = 0;
262266
virtual bool OnNotificationOperatingModeTopic(kortex_driver::OnNotificationOperatingModeTopic::Request &req, kortex_driver::OnNotificationOperatingModeTopic::Response &res) = 0;
263267
virtual void cb_OperatingModeTopic(Kinova::Api::Base::OperatingModeNotification notif) = 0;
@@ -349,12 +353,16 @@ class IBaseServices
349353
virtual bool DeleteAllSequenceTasks(kortex_driver::DeleteAllSequenceTasks::Request &req, kortex_driver::DeleteAllSequenceTasks::Response &res) = 0;
350354
virtual bool TakeSnapshot(kortex_driver::TakeSnapshot::Request &req, kortex_driver::TakeSnapshot::Response &res) = 0;
351355
virtual bool GetFirmwareBundleVersions(kortex_driver::GetFirmwareBundleVersions::Request &req, kortex_driver::GetFirmwareBundleVersions::Response &res) = 0;
356+
virtual bool ExecuteWaypointTrajectory(kortex_driver::ExecuteWaypointTrajectory::Request &req, kortex_driver::ExecuteWaypointTrajectory::Response &res) = 0;
352357
virtual bool MoveSequenceTask(kortex_driver::MoveSequenceTask::Request &req, kortex_driver::MoveSequenceTask::Response &res) = 0;
353358
virtual bool DuplicateMapping(kortex_driver::DuplicateMapping::Request &req, kortex_driver::DuplicateMapping::Response &res) = 0;
354359
virtual bool DuplicateMap(kortex_driver::DuplicateMap::Request &req, kortex_driver::DuplicateMap::Response &res) = 0;
355360
virtual bool SetControllerConfiguration(kortex_driver::SetControllerConfiguration::Request &req, kortex_driver::SetControllerConfiguration::Response &res) = 0;
356361
virtual bool GetControllerConfiguration(kortex_driver::GetControllerConfiguration::Request &req, kortex_driver::GetControllerConfiguration::Response &res) = 0;
357362
virtual bool GetAllControllerConfigurations(kortex_driver::GetAllControllerConfigurations::Request &req, kortex_driver::GetAllControllerConfigurations::Response &res) = 0;
363+
virtual bool ComputeForwardKinematics(kortex_driver::ComputeForwardKinematics::Request &req, kortex_driver::ComputeForwardKinematics::Response &res) = 0;
364+
virtual bool ComputeInverseKinematics(kortex_driver::ComputeInverseKinematics::Request &req, kortex_driver::ComputeInverseKinematics::Response &res) = 0;
365+
virtual bool ValidateWaypointList(kortex_driver::ValidateWaypointList::Request &req, kortex_driver::ValidateWaypointList::Response &res) = 0;
358366

359367
protected:
360368
ros::NodeHandle m_node_handle;
@@ -449,7 +457,7 @@ class IBaseServices
449457
ros::ServiceServer m_serviceBase_Unsubscribe;
450458
ros::ServiceServer m_serviceOnNotificationConfigurationChangeTopic;
451459
ros::ServiceServer m_serviceOnNotificationMappingInfoTopic;
452-
ros::ServiceServer m_serviceOnNotificationControlModeTopic;
460+
ros::ServiceServer m_serviceBase_OnNotificationControlModeTopic;
453461
ros::ServiceServer m_serviceOnNotificationOperatingModeTopic;
454462
ros::ServiceServer m_serviceOnNotificationSequenceInfoTopic;
455463
ros::ServiceServer m_serviceOnNotificationProtectionZoneTopic;
@@ -529,11 +537,15 @@ class IBaseServices
529537
ros::ServiceServer m_serviceDeleteAllSequenceTasks;
530538
ros::ServiceServer m_serviceTakeSnapshot;
531539
ros::ServiceServer m_serviceGetFirmwareBundleVersions;
540+
ros::ServiceServer m_serviceExecuteWaypointTrajectory;
532541
ros::ServiceServer m_serviceMoveSequenceTask;
533542
ros::ServiceServer m_serviceDuplicateMapping;
534543
ros::ServiceServer m_serviceDuplicateMap;
535544
ros::ServiceServer m_serviceSetControllerConfiguration;
536545
ros::ServiceServer m_serviceGetControllerConfiguration;
537546
ros::ServiceServer m_serviceGetAllControllerConfigurations;
547+
ros::ServiceServer m_serviceComputeForwardKinematics;
548+
ros::ServiceServer m_serviceComputeInverseKinematics;
549+
ros::ServiceServer m_serviceValidateWaypointList;
538550
};
539551
#endif

kortex_driver/include/kortex_driver/generated/interfaces/controlconfig_services_interface.h

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -54,6 +54,8 @@
5454
#include "kortex_driver/ResetTwistLinearSoftLimit.h"
5555
#include "kortex_driver/ResetTwistAngularSoftLimit.h"
5656
#include "kortex_driver/ResetJointAccelerationSoftLimits.h"
57+
#include "kortex_driver/ControlConfig_OnNotificationControlModeTopic.h"
58+
#include "kortex_driver/ControlConfig_ControlModeNotification.h"
5759

5860
#include "kortex_driver/KortexError.h"
5961
#include "kortex_driver/SetDeviceID.h"
@@ -99,12 +101,16 @@ class IControlConfigServices
99101
virtual bool ResetTwistLinearSoftLimit(kortex_driver::ResetTwistLinearSoftLimit::Request &req, kortex_driver::ResetTwistLinearSoftLimit::Response &res) = 0;
100102
virtual bool ResetTwistAngularSoftLimit(kortex_driver::ResetTwistAngularSoftLimit::Request &req, kortex_driver::ResetTwistAngularSoftLimit::Response &res) = 0;
101103
virtual bool ResetJointAccelerationSoftLimits(kortex_driver::ResetJointAccelerationSoftLimits::Request &req, kortex_driver::ResetJointAccelerationSoftLimits::Response &res) = 0;
104+
virtual bool ControlConfig_OnNotificationControlModeTopic(kortex_driver::ControlConfig_OnNotificationControlModeTopic::Request &req, kortex_driver::ControlConfig_OnNotificationControlModeTopic::Response &res) = 0;
105+
virtual void cb_ControlModeTopic(Kinova::Api::ControlConfig::ControlModeNotification notif) = 0;
102106

103107
protected:
104108
ros::NodeHandle m_node_handle;
105109
ros::Publisher m_pub_Error;
106110
ros::Publisher m_pub_ControlConfigurationTopic;
107111
bool m_is_activated_ControlConfigurationTopic;
112+
ros::Publisher m_pub_ControlModeTopic;
113+
bool m_is_activated_ControlModeTopic;
108114

109115
ros::ServiceServer m_serviceSetDeviceID;
110116
ros::ServiceServer m_serviceSetApiOptions;
@@ -138,5 +144,6 @@ class IControlConfigServices
138144
ros::ServiceServer m_serviceResetTwistLinearSoftLimit;
139145
ros::ServiceServer m_serviceResetTwistAngularSoftLimit;
140146
ros::ServiceServer m_serviceResetJointAccelerationSoftLimits;
147+
ros::ServiceServer m_serviceControlConfig_OnNotificationControlModeTopic;
141148
};
142149
#endif

kortex_driver/include/kortex_driver/generated/robot/base_proto_converter.h

Lines changed: 26 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,9 @@
4141
#include "kortex_driver/generated/robot/visionconfig_proto_converter.h"
4242

4343

44+
#include "kortex_driver/GpioConfigurationList.h"
45+
#include "kortex_driver/Base_GpioConfiguration.h"
46+
#include "kortex_driver/GpioPinConfiguration.h"
4447
#include "kortex_driver/FullUserProfile.h"
4548
#include "kortex_driver/UserProfile.h"
4649
#include "kortex_driver/UserProfileList.h"
@@ -99,7 +102,7 @@
99102
#include "kortex_driver/ConfigurationChangeNotification.h"
100103
#include "kortex_driver/MappingInfoNotification.h"
101104
#include "kortex_driver/Base_ControlModeInformation.h"
102-
#include "kortex_driver/ControlModeNotification.h"
105+
#include "kortex_driver/Base_ControlModeNotification.h"
103106
#include "kortex_driver/ServoingModeInformation.h"
104107
#include "kortex_driver/OperatingModeInformation.h"
105108
#include "kortex_driver/OperatingModeNotification.h"
@@ -116,6 +119,7 @@
116119
#include "kortex_driver/ControllerState.h"
117120
#include "kortex_driver/ControllerElementState.h"
118121
#include "kortex_driver/ActionNotification.h"
122+
#include "kortex_driver/TrajectoryInfo.h"
119123
#include "kortex_driver/ActionExecutionState.h"
120124
#include "kortex_driver/RobotEventNotification.h"
121125
#include "kortex_driver/FactoryNotification.h"
@@ -176,6 +180,7 @@
176180
#include "kortex_driver/GripperRequest.h"
177181
#include "kortex_driver/Gripper.h"
178182
#include "kortex_driver/Finger.h"
183+
#include "kortex_driver/GpioCommand.h"
179184
#include "kortex_driver/SystemTime.h"
180185
#include "kortex_driver/ControllerConfigurationMode.h"
181186
#include "kortex_driver/ControllerConfiguration.h"
@@ -193,10 +198,20 @@
193198
#include "kortex_driver/PreComputedJointTrajectoryElement.h"
194199
#include "kortex_driver/TrajectoryErrorElement.h"
195200
#include "kortex_driver/TrajectoryErrorReport.h"
201+
#include "kortex_driver/WaypointValidationReport.h"
202+
#include "kortex_driver/Waypoint.h"
203+
#include "kortex_driver/AngularWaypoint.h"
204+
#include "kortex_driver/CartesianWaypoint.h"
205+
#include "kortex_driver/WaypointList.h"
206+
#include "kortex_driver/KinematicTrajectoryConstraints.h"
196207
#include "kortex_driver/FirmwareBundleVersions.h"
197208
#include "kortex_driver/FirmwareComponentVersion.h"
209+
#include "kortex_driver/IKData.h"
198210

199211

212+
int ToProtoData(kortex_driver::GpioConfigurationList input, Kinova::Api::Base::GpioConfigurationList *output);
213+
int ToProtoData(kortex_driver::Base_GpioConfiguration input, Kinova::Api::Base::GpioConfiguration *output);
214+
int ToProtoData(kortex_driver::GpioPinConfiguration input, Kinova::Api::Base::GpioPinConfiguration *output);
200215
int ToProtoData(kortex_driver::FullUserProfile input, Kinova::Api::Base::FullUserProfile *output);
201216
int ToProtoData(kortex_driver::UserProfile input, Kinova::Api::Base::UserProfile *output);
202217
int ToProtoData(kortex_driver::UserProfileList input, Kinova::Api::Base::UserProfileList *output);
@@ -255,7 +270,7 @@ int ToProtoData(kortex_driver::Query input, Kinova::Api::Base::Query *output);
255270
int ToProtoData(kortex_driver::ConfigurationChangeNotification input, Kinova::Api::Base::ConfigurationChangeNotification *output);
256271
int ToProtoData(kortex_driver::MappingInfoNotification input, Kinova::Api::Base::MappingInfoNotification *output);
257272
int ToProtoData(kortex_driver::Base_ControlModeInformation input, Kinova::Api::Base::ControlModeInformation *output);
258-
int ToProtoData(kortex_driver::ControlModeNotification input, Kinova::Api::Base::ControlModeNotification *output);
273+
int ToProtoData(kortex_driver::Base_ControlModeNotification input, Kinova::Api::Base::ControlModeNotification *output);
259274
int ToProtoData(kortex_driver::ServoingModeInformation input, Kinova::Api::Base::ServoingModeInformation *output);
260275
int ToProtoData(kortex_driver::OperatingModeInformation input, Kinova::Api::Base::OperatingModeInformation *output);
261276
int ToProtoData(kortex_driver::OperatingModeNotification input, Kinova::Api::Base::OperatingModeNotification *output);
@@ -272,6 +287,7 @@ int ToProtoData(kortex_driver::ControllerList input, Kinova::Api::Base::Controll
272287
int ToProtoData(kortex_driver::ControllerState input, Kinova::Api::Base::ControllerState *output);
273288
int ToProtoData(kortex_driver::ControllerElementState input, Kinova::Api::Base::ControllerElementState *output);
274289
int ToProtoData(kortex_driver::ActionNotification input, Kinova::Api::Base::ActionNotification *output);
290+
int ToProtoData(kortex_driver::TrajectoryInfo input, Kinova::Api::Base::TrajectoryInfo *output);
275291
int ToProtoData(kortex_driver::ActionExecutionState input, Kinova::Api::Base::ActionExecutionState *output);
276292
int ToProtoData(kortex_driver::RobotEventNotification input, Kinova::Api::Base::RobotEventNotification *output);
277293
int ToProtoData(kortex_driver::FactoryNotification input, Kinova::Api::Base::FactoryNotification *output);
@@ -332,6 +348,7 @@ int ToProtoData(kortex_driver::GripperCommand input, Kinova::Api::Base::GripperC
332348
int ToProtoData(kortex_driver::GripperRequest input, Kinova::Api::Base::GripperRequest *output);
333349
int ToProtoData(kortex_driver::Gripper input, Kinova::Api::Base::Gripper *output);
334350
int ToProtoData(kortex_driver::Finger input, Kinova::Api::Base::Finger *output);
351+
int ToProtoData(kortex_driver::GpioCommand input, Kinova::Api::Base::GpioCommand *output);
335352
int ToProtoData(kortex_driver::SystemTime input, Kinova::Api::Base::SystemTime *output);
336353
int ToProtoData(kortex_driver::ControllerConfigurationMode input, Kinova::Api::Base::ControllerConfigurationMode *output);
337354
int ToProtoData(kortex_driver::ControllerConfiguration input, Kinova::Api::Base::ControllerConfiguration *output);
@@ -349,7 +366,14 @@ int ToProtoData(kortex_driver::PreComputedJointTrajectory input, Kinova::Api::Ba
349366
int ToProtoData(kortex_driver::PreComputedJointTrajectoryElement input, Kinova::Api::Base::PreComputedJointTrajectoryElement *output);
350367
int ToProtoData(kortex_driver::TrajectoryErrorElement input, Kinova::Api::Base::TrajectoryErrorElement *output);
351368
int ToProtoData(kortex_driver::TrajectoryErrorReport input, Kinova::Api::Base::TrajectoryErrorReport *output);
369+
int ToProtoData(kortex_driver::WaypointValidationReport input, Kinova::Api::Base::WaypointValidationReport *output);
370+
int ToProtoData(kortex_driver::Waypoint input, Kinova::Api::Base::Waypoint *output);
371+
int ToProtoData(kortex_driver::AngularWaypoint input, Kinova::Api::Base::AngularWaypoint *output);
372+
int ToProtoData(kortex_driver::CartesianWaypoint input, Kinova::Api::Base::CartesianWaypoint *output);
373+
int ToProtoData(kortex_driver::WaypointList input, Kinova::Api::Base::WaypointList *output);
374+
int ToProtoData(kortex_driver::KinematicTrajectoryConstraints input, Kinova::Api::Base::KinematicTrajectoryConstraints *output);
352375
int ToProtoData(kortex_driver::FirmwareBundleVersions input, Kinova::Api::Base::FirmwareBundleVersions *output);
353376
int ToProtoData(kortex_driver::FirmwareComponentVersion input, Kinova::Api::Base::FirmwareComponentVersion *output);
377+
int ToProtoData(kortex_driver::IKData input, Kinova::Api::Base::IKData *output);
354378

355379
#endif

0 commit comments

Comments
 (0)