Skip to content

Commit

Permalink
Merge pull request #23 from helix-robotics-ag/seb/add_helix_control_i…
Browse files Browse the repository at this point in the history
…nterfaces

Seb/add helix control interfaces
  • Loading branch information
sebtiburzio authored Jul 8, 2024
2 parents 587b088 + 0391057 commit c008951
Show file tree
Hide file tree
Showing 5 changed files with 30 additions and 0 deletions.
5 changes: 5 additions & 0 deletions helix_transmission_interfaces/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,10 +6,15 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
endif()

find_package(ament_cmake REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(rosidl_default_generators REQUIRED)

rosidl_generate_interfaces(${PROJECT_NAME}
"srv/SetCurrent.srv"
"srv/GoToGripperPoseVector.srv"
"srv/GoToGripperPoseQuat.srv"
"srv/GoToGripperPoseEuler.srv"
DEPENDENCIES geometry_msgs
)

ament_package()
1 change: 1 addition & 0 deletions helix_transmission_interfaces/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>geometry_msgs</depend>
<buildtool_depend>rosidl_default_generators</buildtool_depend>
<exec_depend>rosidl_default_runtime</exec_depend>
<member_of_group>rosidl_interface_packages</member_of_group>
Expand Down
9 changes: 9 additions & 0 deletions helix_transmission_interfaces/srv/GoToGripperPoseEuler.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
string frame_id
geometry_msgs/Point goal_point
float64[3] goal_euler_angs
string axes "sxyz"
bool plan_linear
bool ik_uses_prev
---
bool success
string message
7 changes: 7 additions & 0 deletions helix_transmission_interfaces/srv/GoToGripperPoseQuat.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
string frame_id
geometry_msgs/Pose goal_pose
bool plan_linear
bool ik_uses_prev
---
bool success
string message
8 changes: 8 additions & 0 deletions helix_transmission_interfaces/srv/GoToGripperPoseVector.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
string frame_id
geometry_msgs/Point goal_point
geometry_msgs/Vector3 goal_direction
bool plan_linear
bool ik_uses_prev
---
bool success
string message

0 comments on commit c008951

Please sign in to comment.