From 7b3e64ff8db0391a464f53038768c7d52fd006ad Mon Sep 17 00:00:00 2001 From: SebastianEbert <sebastian.ebert@tu-dresden.de> Date: Wed, 8 Apr 2020 10:54:50 +0200 Subject: [PATCH] documentation of mqtt-interfaces --- README.md | 52 ++++++++++++++++++++++++++++++++++++++ src/RobotStateProvider.cpp | 6 ++--- 2 files changed, 55 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index 1e746f7..c2ba625 100644 --- a/README.md +++ b/README.md @@ -77,6 +77,58 @@ $ sudo ldconfig (source: https://github.com/eclipse/paho.mqtt.cpp/blob/master/README.md) +## Provided MQTT-Interfaces + +### Configuration of the data-stream (ROS -> RAG) + +#### General + +* Channel: dataconfig +* Protobuff-message format defined in ../panda_simulation/src/proto/dataconfig.proto +* Changes submitted data starting from the next data-package retreived from gazebo + +#### Parameter + +* Parameter "data_publish_rate" means in which intervals messages are pulled out of gazebo's data stream +* data_enable_position, true -> send joint positions +* data_enable_orientation, true -> send joint orientations +* data_enable_twist_linear, true -> sent linear twists of joints +* data_enable_twist_angular, true -> sent angular twists of joints + +### Configuration of the simulated robot + +#### General + +* Channel: robotconfig +* Protobuff-message format defined in ../panda_simulation/src/proto/robotconfig.proto + +#### Parameter + +* robot_speed_factor, defines how fast the robot moves starting from the next trajectory-point +* is a factor multiplied to the speed computed by the trajectory-planning algorithm +* Range: 0,1 to 1,0 (recommed are values > 0.3) + +### Datastream format + +#### General + +* Data for every link has its own mqtt-channel (defined in section bellow) +* Protobuff-message format defined in ../panda_simulation/src/proto/linkstate.proto + +#### Channels + +* panda_ground: ground-plate +* panda_link_0: link_0 of the panda +* panda_link_1: link_1 of the panda +* panda_link_2: link_2 of the panda +* panda_link_3: link_3 of the panda +* panda_link_4: link_4 of the panda +* panda_link_5: link_5 of the panda +* panda_link_6: link_6 of the panda +* panda_link_7: link_7 of the panda (end effector) +* panda_link_8: link_8 of the panda (left finger) +* panda_link_9: link_9 of the panda (right finger) + ## Changelog #### Safetyzones diff --git a/src/RobotStateProvider.cpp b/src/RobotStateProvider.cpp index cfd6878..c91f02c 100644 --- a/src/RobotStateProvider.cpp +++ b/src/RobotStateProvider.cpp @@ -14,9 +14,9 @@ bool export_to_log = false; * mqtt-topics for all links * ground, link0, link1, link2, link3, link4, link5, link6, link7 (end-effector), left finger, right finder */ -std::string topics[11] = {"panda_link_0", "panda_link_1", "panda_link_2", "panda_link_3", - "panda_link_4", "panda_link_5", "panda_link_6", "panda_link_7", - "panda_link_8", "panda_link_9", "panda_link_10"}; +std::string topics[11] = {"panda_ground", "panda_link_0", "panda_link_1", "panda_link_2", + "panda_link_3", "panda_link_4", "panda_link_5", "panda_link_6", + "panda_link_7", "panda_link_8", "panda_link_9"}; bool mqttSetup = false; bool isInitialized = false; -- GitLab