From 0538dae694342320a9c60db71114d8cd0c25f78c Mon Sep 17 00:00:00 2001
From: Johannes Mey <johannes.mey@tu-dresden.de>
Date: Mon, 8 Jun 2020 13:55:28 +0200
Subject: [PATCH] align names with ros package

---
 config/panda_control.yaml       | 3 ++-
 launch/simulation.launch        | 5 ++---
 src/robot_state_initializer.cpp | 8 ++++----
 3 files changed, 8 insertions(+), 8 deletions(-)

diff --git a/config/panda_control.yaml b/config/panda_control.yaml
index 94c10f3..65fcaf7 100644
--- a/config/panda_control.yaml
+++ b/config/panda_control.yaml
@@ -3,7 +3,7 @@
         type: joint_state_controller/JointStateController
         publish_rate: 100
 
-    panda_arm_controller:
+    position_joint_trajectory_controller:
         type: position_controllers/JointTrajectoryController
         joints:
             - panda_joint1
@@ -26,6 +26,7 @@
             - panda_finger_joint2
 
         state_publish_rate: 25
+
     joint_position_controller:
         type: panda_simulation/JointPositionController
         arm_id: panda
diff --git a/launch/simulation.launch b/launch/simulation.launch
index f1972ca..3678504 100644
--- a/launch/simulation.launch
+++ b/launch/simulation.launch
@@ -9,9 +9,8 @@
     <arg name="load_gripper" default="true" />
 
     <!-- don't include franka_control, but include the controller stuff from there -->
-  <param name="robot_description" command="$(find xacro)/xacro --inorder '$(find franka_description)/robots/panda_arm_hand.urdf.xacro'" if="$(arg load_gripper)" />
-  <param name="robot_description" command="$(find xacro)/xacro --inorder '$(find franka_description)/robots/panda_arm.urdf.xacro'" unless="$(arg load_gripper)" />
-    <rosparam command="load" file="$(find franka_control)/config/default_controllers.yaml" />
+  <param name="robot_description" command="$(find xacro)/xacro '$(find franka_description)/robots/panda_arm_hand.urdf.xacro'" if="$(arg load_gripper)" />
+  <param name="robot_description" command="$(find xacro)/xacro '$(find franka_description)/robots/panda_arm.urdf.xacro'" unless="$(arg load_gripper)" />
 
     <!--launch GAZEBO with own world configuration -->
     <include file="$(find gazebo_ros)/launch/empty_world.launch">
diff --git a/src/robot_state_initializer.cpp b/src/robot_state_initializer.cpp
index 4c6626d..49932e2 100644
--- a/src/robot_state_initializer.cpp
+++ b/src/robot_state_initializer.cpp
@@ -62,11 +62,11 @@ int main(int argc, char **argv) {
   srv_switch_controller.request.start_controllers = start_controllers;
 
   if (switch_controller_client.call(srv_switch_controller)) {
-    ROS_INFO_STREAM("Success switching controllers from " << stream_stop_controllers.str() << " to "
-                                                          << stream_start_controllers.str());
+    ROS_INFO_STREAM("Success switching controllers from " << stream_start_controllers.str() << " to "
+                                                          << stream_stop_controllers.str());
   } else {
-    ROS_WARN_STREAM("Error switching controllers from " << stream_stop_controllers.str() << " to "
-                                                        << stream_start_controllers.str());
+    ROS_WARN_STREAM("Error switching controllers from " << stream_start_controllers.str() << " to "
+                                                        << stream_stop_controllers.str());
     return -1;
   }
 
-- 
GitLab