Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
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
16 changes: 12 additions & 4 deletions control_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,15 +10,17 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

find_package(action_msgs REQUIRED)
find_package(ament_cmake REQUIRED)
find_package(builtin_interfaces REQUIRED)
find_package(rosidl_default_generators REQUIRED)
find_package(action_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(rosidl_default_generators REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(std_msgs REQUIRED)
find_package(trajectory_msgs REQUIRED)

set(msg_files
msg/AdmittanceControllerState.msg
msg/DynamicJointState.msg
msg/GripperCommand.msg
msg/InterfaceValue.msg
Expand Down Expand Up @@ -49,10 +51,16 @@ if(BUILD_TESTING)
endif()

rosidl_generate_interfaces(${PROJECT_NAME}
${action_files}
${msg_files}
${srv_files}
${action_files}
DEPENDENCIES action_msgs builtin_interfaces geometry_msgs std_msgs trajectory_msgs
DEPENDENCIES
action_msgs
builtin_interfaces
geometry_msgs
sensor_msgs
std_msgs
trajectory_msgs
ADD_LINTER_TESTS
)
ament_export_dependencies(rosidl_default_runtime)
Expand Down
17 changes: 17 additions & 0 deletions control_msgs/msg/AdmittanceControllerState.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
# Admittance parameters
std_msgs/Float64MultiArray mass # 6-vector of mass terms used in the admittance calculation
std_msgs/Float64MultiArray damping # 6-vector of damping terms used in the admittance calculation
std_msgs/Float64MultiArray stiffness # 6-vector of stiffness terms used in the admittance calculation

# Frame information
geometry_msgs/Quaternion rot_base_control # quaternion describing the orientation of the control frame
geometry_msgs/TransformStamped ref_trans_base_ft # force torque sensor transform at the reference joint configuration
std_msgs/Int8MultiArray selected_axes # 6-vector of 0/1 describing if admittance is enable in the corresponding control frame axis
std_msgs/String ft_sensor_frame # name of the force torque frame

# State information
geometry_msgs/TransformStamped admittance_position # calculated admittance position in cartesian space
geometry_msgs/TwistStamped admittance_acceleration # calculated admittance acceleration in cartesian space
geometry_msgs/TwistStamped admittance_velocity # calculated admittance velocity in cartesian space
geometry_msgs/WrenchStamped wrench_base # wrench used in the admittance calculation
sensor_msgs/JointState joint_state # calculated admittance offsets in joint space
1 change: 1 addition & 0 deletions control_msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
<depend>action_msgs</depend>
<depend>builtin_interfaces</depend>
<depend>geometry_msgs</depend>
<depend>sensor_msgs</depend>
<depend>std_msgs</depend>
<depend>trajectory_msgs</depend>

Expand Down