Skip to content

Commit

Permalink
msg&srv file update / read_data_rt client to torque_rt_stream publish…
Browse files Browse the repository at this point in the history
…er node created
  • Loading branch information
uzchan98 authored and doosan-robotics committed Oct 1, 2024
1 parent 2c10547 commit d6043e7
Show file tree
Hide file tree
Showing 31 changed files with 550 additions and 0 deletions.
6 changes: 6 additions & 0 deletions dsr_msgs2/msg/AlterMotionStream.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
#____________________________________________________________________________________________
# alter_motion
#
#____________________________________________________________________________________________

float64[6] pos # position
92 changes: 92 additions & 0 deletions dsr_msgs2/msg/RobotStateRt.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,92 @@
# timestamp at the data of data acquisition
float64 time_stamp
# actual joint position from incremental encoder at motor side(used for control) [deg]
float64[6] actual_joint_position
# actual joint position from absolute encoder at link side (used for exact link position) [deg]
float64[6] actual_joint_position_abs
# actual joint velocity from incremental encoder at motor side [deg/s]
float64[6] actual_joint_velocity
# actual joint velocity from absolute encoder at link side [deg/s]
float64[6] actual_joint_velocity_abs
# actual robot tcp position w.r.t. base coordinates: (x, y, z, a, b, c), where (a, b, c) follows Euler ZYZ notation [mm, deg]
float64[6] actual_tcp_position
# actual robot tcp velocity w.r.t. base coordinates [mm, deg/s]
float64[6] actual_tcp_velocity
# actual robot flange position w.r.t. base coordinates: (x, y, z, a, b, c), where (a, b, c) follows Euler ZYZ notation [mm, deg]
float64[6] actual_flange_position
# robot flange velocity w.r.t. base coordinates [mm, deg/s]
float64[6] actual_flange_velocity
# actual motor torque applying gear ratio = gear_ratio * current2torque_constant * motor current [Nm]
float64[6] actual_motor_torque
# estimated joint torque by robot controller [Nm]
float64[6] actual_joint_torque
# calibrated joint torque sensor data [Nm]
float64[6] raw_joint_torque
# calibrated force torque sensor data w.r.t. flange coordinates [N, Nm]
float64[6] raw_force_torque
# estimated external joint torque [Nm]
float64[6] external_joint_torque
# estimated tcp force w.r.t. base coordinates [N, Nm]
float64[6] external_tcp_force
# target joint position [deg]
float64[6] target_joint_position
# target joint velocity [deg/s]
float64[6] target_joint_velocity
# target joint acceleration [deg/s^2]
float64[6] target_joint_acceleration
# target motor torque [Nm]
float64[6] target_motor_torque
# target tcp position w.r.t. base coordinates: (x, y, z, a, b, c), where (a, b, c) follows Euler ZYZ notation [mm, deg]
float64[6] target_tcp_position
# target tcp velocity w.r.t. base coordinates [mm, deg/s]
float64[6] target_tcp_velocity
# jacobian matrix=J(q) w.r.t. base coordinates
std_msgs/Float64MultiArray[] jacobian_matrix
# gravity torque=g(q) [Nm]
float64[6] gravity_torque
# coriolis matrix=C(q,q_dot) [6][6]
std_msgs/Float64MultiArray[] coriolis_matrix
# mass matrix=M(q) [6][6]
std_msgs/Float64MultiArray[] mass_matrix
# robot configuration
uint16 solution_space
# minimum singular value
float64 singularity
# current operation speed rate(1~100 %)
float64 operation_speed_rate
# joint temperature(celsius)
float64[6] joint_temperature
# controller digital input(16 channel)
uint16 controller_digital_input
# controller digital output(16 channel)
uint16 controller_digital_output
# controller analog input type(2 channel)
uint8[2] controller_analog_input_type
# controller analog input(2 channel)
float64[2] controller_analog_input
# controller analog output type(2 channel)
uint8[2] controller_analog_output_type
# controller analog output(2 channel)
float64[2] controller_analog_output
# flange digital input(A-Series: 2 channel, M/H-Series: 6 channel)
uint8 flange_digital_input
# flange digital output(A-Series: 2 channel, M/H-Series: 6 channel)
uint8 flange_digital_output
# flange analog input(A-Series: 2 channel, M/H-Series: 4 channel)
float64[4] flange_analog_input
# strobe count(increased by 1 when detecting setting edge)
uint8[2] external_encoder_strobe_count
# external encoder count
uint16[2] external_encoder_count
# final goal joint position (reserved)
float64[6] goal_joint_position
# final goal tcp position (reserved)
float64[6] goal_tcp_position
# ROBOT_MODE_MANUAL(0), ROBOT_MODE_AUTONOMOUS(1), ROBOT_MODE_MEASURE(2)
uint8 robot_mode
# STATE_INITIALIZING(0), STATE_STANDBY(1), STATE_MOVING(2), STATE_SAFE_OFF(3), STATE_TEACHING(4), STATE_SAFE_STOP(5), STATE_EMERGENCY_STOP, STATE_HOMMING, STATE_RECOVERY, STATE_SAFE_STOP2, STATE_SAFE_OFF2,
uint8 robot_state
# position control mode, torque mode
uint16 control_mode
# Reserved
uint8[256] reserved
9 changes: 9 additions & 0 deletions dsr_msgs2/msg/ServojRtStream.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
#____________________________________________________________________________________________
# servoj_rt
#
#____________________________________________________________________________________________

float64[6] pos # position
float64[6] vel # velocity
float64[6] acc # acceleration
float64 time # time
9 changes: 9 additions & 0 deletions dsr_msgs2/msg/ServojStream.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
#____________________________________________________________________________________________
# servoj
#
#____________________________________________________________________________________________

float64[6] pos # position
float64[6] vel # velocity
float64[6] acc # acceleration
float64 time # time
9 changes: 9 additions & 0 deletions dsr_msgs2/msg/ServolRtStream.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
#____________________________________________________________________________________________
# servol_rt
#
#____________________________________________________________________________________________

float64[6] pos # position
float64[6] vel # velocity
float64[6] acc # acceleration
float64 time # time
9 changes: 9 additions & 0 deletions dsr_msgs2/msg/ServolStream.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
#____________________________________________________________________________________________
# servol
#
#____________________________________________________________________________________________

float64[6] pos # position
float64[2] vel # velocity
float64[2] acc # acceleration
float64 time # time
8 changes: 8 additions & 0 deletions dsr_msgs2/msg/SpeedjRtStream.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
#____________________________________________________________________________________________
# speedj_rt
#
#____________________________________________________________________________________________

float64[6] vel # velocity
float64[6] acc # acceleration
float64 time # time
8 changes: 8 additions & 0 deletions dsr_msgs2/msg/SpeedjStream.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
#____________________________________________________________________________________________
# speedj
#
#____________________________________________________________________________________________

float64[6] vel # velocity
float64[6] acc # acceleration
float64 time # time
8 changes: 8 additions & 0 deletions dsr_msgs2/msg/SpeedlRtStream.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
#____________________________________________________________________________________________
# speedl_rt
#
#____________________________________________________________________________________________

float64[6] vel # velocity
float64[6] acc # acceleration
float64 time # time
8 changes: 8 additions & 0 deletions dsr_msgs2/msg/SpeedlStream.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
#____________________________________________________________________________________________
# speedl
#
#____________________________________________________________________________________________

float64[6] vel # velocity
float64[2] acc # acceleration
float64 time # time
7 changes: 7 additions & 0 deletions dsr_msgs2/msg/TorqueRtStream.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
#____________________________________________________________________________________________
# torque_rt
#
#____________________________________________________________________________________________

float64[6] tor # motor torque
float64 time # time
8 changes: 8 additions & 0 deletions dsr_msgs2/srv/realtime/ConnectRtControl.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
#____________________________________________________________________________________________
# connect_rt_control
#____________________________________________________________________________________________

string ip_address
uint32 port
---
bool success
5 changes: 5 additions & 0 deletions dsr_msgs2/srv/realtime/DisconnectRtControl.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
#____________________________________________________________________________________________
# disconnect_rt_control
#____________________________________________________________________________________________
---
bool success
7 changes: 7 additions & 0 deletions dsr_msgs2/srv/realtime/GetRtControlInputDataList.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
#____________________________________________________________________________________________
# get_rt_control_input_data_list
#____________________________________________________________________________________________
string version
---
bool success
string data
7 changes: 7 additions & 0 deletions dsr_msgs2/srv/realtime/GetRtControlInputVersionList.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
#____________________________________________________________________________________________
# get_rt_control_input_version_list
#____________________________________________________________________________________________

---
bool success
string version
8 changes: 8 additions & 0 deletions dsr_msgs2/srv/realtime/GetRtControlOutputDataList.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
#____________________________________________________________________________________________
# get_rt_control_output_data_list
#____________________________________________________________________________________________

string version
---
bool success
string data
7 changes: 7 additions & 0 deletions dsr_msgs2/srv/realtime/GetRtControlOutputVersionList.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
#____________________________________________________________________________________________
# get_rt_control_output_version_list
#____________________________________________________________________________________________

---
bool success
string version
6 changes: 6 additions & 0 deletions dsr_msgs2/srv/realtime/ReadDataRt.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
#____________________________________________________________________________________________
# read_data_rt
#____________________________________________________________________________________________

---
RobotStateRt data
6 changes: 6 additions & 0 deletions dsr_msgs2/srv/realtime/SetAccjRt.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
#____________________________________________________________________________________________
# set_accj_rt
#____________________________________________________________________________________________
float64[6] acc
---
bool success
7 changes: 7 additions & 0 deletions dsr_msgs2/srv/realtime/SetAccxRt.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
#____________________________________________________________________________________________
# set_accx_rt
#____________________________________________________________________________________________
float64 trans
float64 rotation
---
bool success
8 changes: 8 additions & 0 deletions dsr_msgs2/srv/realtime/SetRtControlInput.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
#____________________________________________________________________________________________
# set_rt_control_input
#____________________________________________________________________________________________
string version
float64 period
int32 loss
---
bool success
8 changes: 8 additions & 0 deletions dsr_msgs2/srv/realtime/SetRtControlOutput.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
#____________________________________________________________________________________________
# set_rt_control_output
#____________________________________________________________________________________________
string version
float64 period
int32 loss
---
bool success
6 changes: 6 additions & 0 deletions dsr_msgs2/srv/realtime/SetVeljRt.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
#____________________________________________________________________________________________
# set_velj_rt
#____________________________________________________________________________________________
float64[6] vel
---
bool success
7 changes: 7 additions & 0 deletions dsr_msgs2/srv/realtime/SetVelxRt.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
#____________________________________________________________________________________________
# set_velx_rt
#____________________________________________________________________________________________
float64 trans
float64 rotation
---
bool success
6 changes: 6 additions & 0 deletions dsr_msgs2/srv/realtime/StartRtControl.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
#____________________________________________________________________________________________
# start_rt_control
#____________________________________________________________________________________________

---
bool success
5 changes: 5 additions & 0 deletions dsr_msgs2/srv/realtime/StopRtControl.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
#____________________________________________________________________________________________
# stop_rt_control
#____________________________________________________________________________________________
---
bool success
10 changes: 10 additions & 0 deletions dsr_msgs2/srv/realtime/WriteDataRt.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
#____________________________________________________________________________________________
# write_data_rt
#____________________________________________________________________________________________
float64[6] external_force_torque
int32 external_digital_input
int32 external_digital_output
float64[6] external_analog_input
float64[6] external_analog_output
---
bool success
49 changes: 49 additions & 0 deletions dsr_realtime_control/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
cmake_minimum_required(VERSION 3.8)
project(dsr_realtime_control)

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(example_interfaces REQUIRED)
find_package(std_msgs REQUIRED)
find_package(dsr_msgs2 REQUIRED)

SET( COMMON_INC_FILES
../common2/include
)
SET( COMMON_LIB_FILES
../common2/lib
)

include_directories(
include
${Boost_INCLUDE_DIRS}
${COMMON_INC_FILES}
)

LINK_LIBRARIES(DRFL PocoFoundation PocoNet)

if($ENV{ROS_DISTRO} STREQUAL "humble")
LINK_DIRECTORIES ("${COMMON_LIB_FILES}/$ENV{ROS_DISTRO}/x86_64")
else()
message("Unknown ROS distro:")
message($ENV{ROS_DISTRO})
endif()

add_executable(client_to_publish src/client_to_publish.cpp)
ament_target_dependencies(client_to_publish rclcpp dsr_msgs2)


install(TARGETS
client_to_publish
DESTINATION lib/${PROJECT_NAME}
)

install(DIRECTORY include/
DESTINATION include/${PROJECT_NAME}
)

ament_package()
Loading

0 comments on commit d6043e7

Please sign in to comment.