diff --git a/CMakeLists.txt b/CMakeLists.txt index 8fa7df5..2f3b8d7 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -46,7 +46,6 @@ find_package(catkin REQUIRED message_generation std_msgs) add_message_files( FILES AxisState.msg - AxisDelta.msg Proximity.msg AnalogVoltage.msg ) diff --git a/msg/AxisDelta.msg b/msg/AxisDelta.msg deleted file mode 100644 index 58db60c..0000000 --- a/msg/AxisDelta.msg +++ /dev/null @@ -1,6 +0,0 @@ -# Reports the delta/difference between the current axis state and the prior axis state. - -Header header # Includes a timestamp and frame ID for the measurement. -float64 delta_position # The change in position of the axis in radians. -float64 delta_velocity # The change in velocity of the axis in radians/second. -float64 delta_acceleration # The change in acceleration of the axis in radians/second^2. diff --git a/sensor_msgs_ext.pro b/sensor_msgs_ext.pro index 42205a7..1014e7a 100644 --- a/sensor_msgs_ext.pro +++ b/sensor_msgs_ext.pro @@ -6,7 +6,6 @@ CONFIG -= qt DISTFILES += \ CMakeLists.txt \ msg/AnalogVoltage.msg \ - msg/AxisDelta.msg \ msg/AxisState.msg \ msg/Proximity.msg \ package.xml \