From c1b7b67fb6aa947ee09e4b1d16ea74e4daeccfd1 Mon Sep 17 00:00:00 2001 From: Johannes Mey <johannes.mey@tu-dresden.de> Date: Tue, 14 Jul 2020 08:27:11 +0200 Subject: [PATCH] align config with ros2rag --- config/config.yaml | 10 +++++++++- src/MqttRosConnectionTestNode.cpp | 2 +- src/MqttToRosNode.cpp | 2 +- 3 files changed, 11 insertions(+), 3 deletions(-) diff --git a/config/config.yaml b/config/config.yaml index 7d0b038..e5c9b01 100644 --- a/config/config.yaml +++ b/config/config.yaml @@ -6,7 +6,8 @@ panda_mqtt_connector: topics: robotConfig: "robotconfig" dataConfig: "dataconfig" - trajectoryConfig: "trajectoryconfig" + trajectory: "trajectory" + nextStep: "ros2rag/nextStep" zone_size: 0.5 zones: - "1 1" @@ -25,3 +26,10 @@ panda_mqtt_connector: end_effectors: panda: EndEffector: "panda::panda_link7" + goal_poses: + - position: "0.4 0.3 0.1" + wait: "5000" + - position: "0.4 0.0 0.1" + wait: "3000" + - position: "0.4 -0.3 0.1" + wait: "4000" diff --git a/src/MqttRosConnectionTestNode.cpp b/src/MqttRosConnectionTestNode.cpp index 321af1e..0bf073e 100644 --- a/src/MqttRosConnectionTestNode.cpp +++ b/src/MqttRosConnectionTestNode.cpp @@ -37,7 +37,7 @@ void testTrajectoryUpdate(const ros::NodeHandle& n) { std::string mqtt_msg; traj.SerializeToString(&mqtt_msg); - auto pubmsg = mqtt::make_message("trajectoryconfig", mqtt_msg); + auto pubmsg = mqtt::make_message("trajectory", mqtt_msg); mqttUtil->getClient().publish(pubmsg); diff --git a/src/MqttToRosNode.cpp b/src/MqttToRosNode.cpp index d7c08ad..da04395 100644 --- a/src/MqttToRosNode.cpp +++ b/src/MqttToRosNode.cpp @@ -13,7 +13,7 @@ const std::string CLIENT_ID{"mqtt_to_ros"}; const std::string ROBOT_CONFIG{"robotconfig"}; const std::string DATA_CONFIG{"dataconfig"}; -const std::string TRAJECTORY_CONFIG{"trajectoryconfig"}; +const std::string TRAJECTORY_CONFIG{"trajectory"}; MqttUtil *mqttUtil = nullptr; -- GitLab