diff --git a/README.md b/README.md
index e06ef02..ea78d3f 100644
--- a/README.md
+++ b/README.md
@@ -208,8 +208,6 @@ catkin_make_isolated --install
## Gazebo
Complimentary information is available in our [documentation's simulation section](https://acutronicrobotics.com/docs/technology/h-ros/api/level1/simulation).
-Launch MARA!
-
```sh
source ~/ros2_mara_ws/install/setup.bash
ros2 launch mara_gazebo mara.launch.py
@@ -223,17 +221,11 @@ ros2 launch mara_gazebo mara.launch.py --urdf mara_robot_gripper_140
*Available urdfs: `mara_robot_gripper_140`, `mara_robot_gripper_140_no_table`, `mara_robot_gripper_85` and `mara_robot_gripper_hande`*
+
+
## RViz
### Launching MARA's Simulation
-Complimentary information is available in our [documentation's simulation section](https://acutronicrobotics.com/docs/technology/h-ros/api/level1/visualization).
-
-Skip this step if you are working with the real MARA.
-
-You can choose one of the available launch files. Let's launch MARA with the Robotiq's S140 Gripper for instance:
-
-```bash
-ros2 launch mara_gazebo mara_gripper_140.launch.py
-```
+You need first to [launch MARA in Gazebo](https://github.com/AcutronicRobotics/MARA#gazebo).
### Visualizing MARA in RViz2
@@ -247,6 +239,8 @@ rviz2 -d `ros2 pkg prefix mara_description`/share/mara_description/rviz/visualiz
Alternatively, instead of using the `robot_description` topic, you can load the 3D model manually selecting the URDF file in RViz.
+
+
## MoveIt!
Motion planning, manipulation, 3D perception, kinematics, control and navigation through brigdes.
@@ -255,7 +249,6 @@ Plan trajectories in a virtual environment with Gazebo and MoveIt!.
#### Terminal 1 (ROS 2.0)
-Launch MARA:
```sh
source ~/ros2_mara_ws/install/setup.bash
ros2 launch mara_gazebo mara.launch.py
@@ -289,12 +282,14 @@ roslaunch mara_bringup mara_bringup_moveit_actions.launch gripper:=true prefix:=
source ~/catkin_mara_ws/devel_isolated/setup.bash
source ~/ros2_mara_ws/install/setup.bash
-ros2 run individual_trajectories_bridge individual_trajectories_bridge_actions -motors ~/ros2_mara_ws/src/mara/individual_trajectories_bridge/config/motors_actions.yaml
+ros2 run individual_trajectories_bridge individual_trajectories_bridge_actions -motors ~/ros2_mara_ws/src/mara/hros_cognition_mara_components/config/motors.yaml sim
```
### MoveIt! with MARA - Real Robot
Plan trajectories in a real environment with MoveIt!.
+:warning: You will need to change the names of the real motors in [MARA/hros_cognition_mara_components](https://github.com/AcutronicRobotics/MARA/blob/master/hros_cognition_mara_components/config/motors.yaml#L10-L15) and in [MARA_ROS1/mara_bringup](https://github.com/AcutronicRobotics/MARA_ROS1/blob/master/mara_bringup/config/motors.yaml#L10-L15) files to match the MACs of your SoMs.
+
#### Terminal 1 (ROS 2.0)
```sh
@@ -316,26 +311,22 @@ ros2 launch mara_bringup mara.launch.py --urdf mara_robot_gripper_140
#### Terminal 2 (ROS)
-You will need to change the [motors.yaml](https://github.com/AcutronicRobotics/MARA_ROS1/blob/master/mara_bringup/config/motors.yaml) file to match the MACs of your SoMs.
-
```sh
source ~/catkin_mara_ws/devel_isolated/setup.bash
-roslaunch mara_bringup mara_bringup_moveit_actions.launch &
+roslaunch mara_bringup mara_bringup_moveit_actions.launch env:=real &
```
If you have used a different urdf in the Terminal 1, you will have to launch the corresponding one to match it:
```sh
-roslaunch mara_bringup mara_bringup_moveit_actions.launch gripper:=true prefix:=140 table:=false &
-roslaunch mara_bringup mara_bringup_moveit_actions.launch gripper:=true prefix:=140 &
-roslaunch mara_bringup mara_bringup_moveit_actions.launch gripper:=true prefix:=85 &
-roslaunch mara_bringup mara_bringup_moveit_actions.launch gripper:=true prefix:=hande &
+roslaunch mara_bringup mara_bringup_moveit_actions.launch env:=real gripper:=true prefix:=140 table:=false &
+roslaunch mara_bringup mara_bringup_moveit_actions.launch env:=real gripper:=true prefix:=140 &
+roslaunch mara_bringup mara_bringup_moveit_actions.launch env:=real gripper:=true prefix:=85 &
+roslaunch mara_bringup mara_bringup_moveit_actions.launch env:=real gripper:=true prefix:=hande &
```
#### Terminal 3 (bridge)
-You will need to change the [motors_actions.yaml](https://github.com/AcutronicRobotics/MARA/blob/master/individual_trajectories_bridge/config/motors_actions.yaml) file to match the MACs of your SoMs (MACs should be the same in this yaml file and in the [motors.yaml](https://github.com/AcutronicRobotics/MARA_ROS1/blob/master/mara_bringup/config/motors.yaml) file of the Terminal 2).
-
```sh
source ~/catkin_mara_ws/devel_isolated/setup.bash
source ~/ros2_mara_ws/install/setup.bash
@@ -343,7 +334,7 @@ source ~/ros2_mara_ws/install/setup.bash
export RMW_IMPLEMENTATION=rmw_opensplice_cpp
export ROS_DOMAIN_ID=22
-ros2 run individual_trajectories_bridge individual_trajectories_bridge_actions -motors ~/ros2_mara_ws/src/mara/individual_trajectories_bridge/config/motors_actions.yaml &
+ros2 run individual_trajectories_bridge individual_trajectories_bridge_actions -motors ~/ros2_mara_ws/src/mara/hros_cognition_mara_components/config/motors.yaml real &
```
diff --git a/hros_cognition_mara_components/CMakeLists.txt b/hros_cognition_mara_components/CMakeLists.txt
index 362bd6c..1c8c297 100644
--- a/hros_cognition_mara_components/CMakeLists.txt
+++ b/hros_cognition_mara_components/CMakeLists.txt
@@ -61,7 +61,7 @@ install( TARGETS
install(
PROGRAMS
- config/link_order.yaml
+ config/motors.yaml
DESTINATION share/${PROJECT_NAME}
)
diff --git a/hros_cognition_mara_components/config/link_order.yaml b/hros_cognition_mara_components/config/link_order.yaml
deleted file mode 100644
index 68ef307..0000000
--- a/hros_cognition_mara_components/config/link_order.yaml
+++ /dev/null
@@ -1,7 +0,0 @@
-motors:
- - hrim_actuation_servomotor_000000000001:axis2
- - hrim_actuation_servomotor_000000000001:axis1
- - hrim_actuation_servomotor_000000000002:axis1
- - hrim_actuation_servomotor_000000000002:axis2
- - hrim_actuation_servomotor_000000000003:axis1
- - hrim_actuation_servomotor_000000000003:axis2
diff --git a/hros_cognition_mara_components/config/motors.yaml b/hros_cognition_mara_components/config/motors.yaml
new file mode 100644
index 0000000..7766d7c
--- /dev/null
+++ b/hros_cognition_mara_components/config/motors.yaml
@@ -0,0 +1,15 @@
+simulated_motors:
+ - "/hrim_actuation_servomotor_000000000001/trajectory_axis2"
+ - "/hrim_actuation_servomotor_000000000001/trajectory_axis1"
+ - "/hrim_actuation_servomotor_000000000002/trajectory_axis1"
+ - "/hrim_actuation_servomotor_000000000002/trajectory_axis2"
+ - "/hrim_actuation_servomotor_000000000003/trajectory_axis1"
+ - "/hrim_actuation_servomotor_000000000003/trajectory_axis2"
+
+real_motors:
+ - "/hrim_actuation_servomotor_70B3D521A042/trajectory_axis2"
+ - "/hrim_actuation_servomotor_70B3D521A042/trajectory_axis1"
+ - "/hrim_actuation_servomotor_70B3D521A08A/trajectory_axis1"
+ - "/hrim_actuation_servomotor_70B3D521A08A/trajectory_axis2"
+ - "/hrim_actuation_servomotor_70B3D521A0A4/trajectory_axis1"
+ - "/hrim_actuation_servomotor_70B3D521A0A4/trajectory_axis2"
diff --git a/hros_cognition_mara_components/include/hros_cognition_mara_components/HROSCognitionMaraComponents.hpp b/hros_cognition_mara_components/include/hros_cognition_mara_components/HROSCognitionMaraComponents.hpp
index 5fee778..337084b 100644
--- a/hros_cognition_mara_components/include/hros_cognition_mara_components/HROSCognitionMaraComponents.hpp
+++ b/hros_cognition_mara_components/include/hros_cognition_mara_components/HROSCognitionMaraComponents.hpp
@@ -80,6 +80,8 @@ class HROSCognitionMaraComponentsNode : public rclcpp::Node
control_msgs::msg::JointTrajectoryControllerState msg_actuators_;
std::string file_motors;
+ std::string environment;
+ std::string motor_key;
std::vector msg_actuators_callback_sync;
diff --git a/hros_cognition_mara_components/src/HROSCognitionMaraComponents.cpp b/hros_cognition_mara_components/src/HROSCognitionMaraComponents.cpp
index fa20189..01d823c 100644
--- a/hros_cognition_mara_components/src/HROSCognitionMaraComponents.cpp
+++ b/hros_cognition_mara_components/src/HROSCognitionMaraComponents.cpp
@@ -42,7 +42,13 @@ HROSCognitionMaraComponentsNode::HROSCognitionMaraComponentsNode(const std::stri
}
std::vector lista_subcribers;
- for (auto motor : config["motors"]) {
+ environment = argv[3];
+ if (environment == "sim")
+ motor_key = "simulated_motors";
+ else if (environment == "real")
+ motor_key = "real_motors";
+
+ for (auto motor : config[motor_key]) {
std::string s = motor.as();
topic_order.push_back(s);
std::cout << "topic name: " << s << std::endl;
@@ -53,30 +59,27 @@ HROSCognitionMaraComponentsNode::HROSCognitionMaraComponentsNode(const std::stri
for(unsigned int i = 0; i < topic_order.size(); i++){
std::string topic = topic_order[i];
- std::string delimiter = ":";
+ std::string delimiter = "trajectory";
std::string id = topic.substr( 0, topic.find(delimiter) );
std::string axis = topic.erase( 0, topic.find(delimiter) + delimiter.length() );
- std::string motor_name = id + "/state_" + axis;
+ std::string motor_name = id + "state" + axis;
auto subscriber = this->create_subscription(
- std::string("/") + motor_name,
+ motor_name,
[this, motor_name](hrim_actuator_rotaryservo_msgs::msg::StateRotaryServo::UniquePtr msg) {
stateCallback(motor_name, msg->velocity, msg->position, msg->effort);
},rmw_qos_profile_sensor_data);
motor_state_subcriptions_.push_back(subscriber);
std::cout << "Subscribe at " << motor_name << std::endl;
- motor_name = id + "/goal_" + axis;
+ motor_name = id + "goal" + axis;
- auto publisher_command = this->create_publisher(
- std::string("/") + motor_name,
- rmw_qos_profile_sensor_data);
+ auto publisher_command = this->create_publisher(motor_name, rmw_qos_profile_sensor_data);
motor_goal_publishers_.push_back(publisher_command);
std::cout << "New publisher at " << motor_name << std::endl;
}
std::cout << "+++++++++++++++++++++++++++++++++++++++++++++++++++++++" << std::endl;
- std::cout << std::endl << std::endl;
msg_actuators_.actual.positions.resize(motor_goal_publishers_.size());
msg_actuators_.actual.velocities.resize(motor_goal_publishers_.size());
@@ -86,14 +89,19 @@ HROSCognitionMaraComponentsNode::HROSCognitionMaraComponentsNode(const std::stri
for(unsigned int i = 0; i < topic_order.size(); i++){
std::string topic = topic_order[i];
- std::string delimiter = ":";
+ std::string delimiter = "trajectory";
std::string id = topic.substr( 0, topic.find(delimiter) );
std::string axis = topic.erase( 0, topic.find(delimiter) + delimiter.length() );
- std::string motor_name = id + "/state_" + axis;
+ std::string motor_name = id + "state" + axis;
msg_actuators_.joint_names[i] = motor_name;
+
+ std::cout << "motor_name: " << motor_name << std::endl;
}
+ std::cout << "+++++++++++++++++++++++++++++++++++++++++++++++++++++++" << std::endl;
+ std::cout << std::endl << std::endl;
+
msg_actuators_callback_sync.resize(topic_order.size());
for(unsigned int i = 0; i < msg_actuators_callback_sync.size(); i++){
msg_actuators_callback_sync[i] = false;
diff --git a/individual_trajectories_bridge/CMakeLists.txt b/individual_trajectories_bridge/CMakeLists.txt
index 35fd348..0e5850d 100644
--- a/individual_trajectories_bridge/CMakeLists.txt
+++ b/individual_trajectories_bridge/CMakeLists.txt
@@ -73,25 +73,6 @@ include_directories(include
${rviz_yaml_cpp_vendor_INCLUDE_DIRS}
)
-add_executable(${PROJECT_NAME} "src/main.cpp")
-
-ament_target_dependencies(${PROJECT_NAME}
- "rclcpp"
- "rclcpp_action"
- "trajectory_msgs"
- "control_msgs"
- "yaml_cpp_vendor"
- ${prefixed_ros1_message_packages}
- ${ros2_message_packages}
- "ros1_roscpp"
- "ros1_control_msgs"
- "ros1_trajectory_msgs"
-)
-
-target_link_libraries(${PROJECT_NAME}
- ${YAML_CPP_LIBRARIES}
-)
-
add_executable(${PROJECT_NAME}_actions
src/main_actions.cpp
src/FollowJointTrajectoryAction.cpp)
@@ -116,11 +97,5 @@ target_link_libraries(${PROJECT_NAME}_actions
${YAML_CPP_LIBRARIES}
)
-install(
- PROGRAMS
- config/motors_actions.yaml
- DESTINATION share/${PROJECT_NAME}
-)
-
-install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_actions
+install(TARGETS ${PROJECT_NAME}_actions
DESTINATION lib/${PROJECT_NAME})
diff --git a/individual_trajectories_bridge/config/motors_actions.yaml b/individual_trajectories_bridge/config/motors_actions.yaml
deleted file mode 100644
index 27c12a0..0000000
--- a/individual_trajectories_bridge/config/motors_actions.yaml
+++ /dev/null
@@ -1,7 +0,0 @@
-motors:
- - "/hrim_actuation_servomotor_000000000001/trajectory_axis2"
- - "/hrim_actuation_servomotor_000000000001/trajectory_axis1"
- - "/hrim_actuation_servomotor_000000000002/trajectory_axis1"
- - "/hrim_actuation_servomotor_000000000002/trajectory_axis2"
- - "/hrim_actuation_servomotor_000000000003/trajectory_axis1"
- - "/hrim_actuation_servomotor_000000000003/trajectory_axis2"
diff --git a/individual_trajectories_bridge/src/main.cpp b/individual_trajectories_bridge/src/main.cpp
deleted file mode 100644
index 2cad43d..0000000
--- a/individual_trajectories_bridge/src/main.cpp
+++ /dev/null
@@ -1,166 +0,0 @@
-#include
-#include
-
-// include ROS 1
-#ifdef __clang__
-# pragma clang diagnostic push
-# pragma clang diagnostic ignored "-Wunused-parameter"
-#endif
-#include "ros/ros.h"
-#include "trajectory_msgs/JointTrajectory.h"
-#include "control_msgs/JointTrajectoryControllerState.h"
-#include "control_msgs/msg/joint_trajectory_controller_state.hpp"
-#include "sensor_msgs/JointState.h"
-#ifdef __clang__
-# pragma clang diagnostic pop
-#endif
-
-// include ROS 2
-#include "rclcpp/rclcpp.hpp"
-#include "trajectory_msgs/msg/joint_trajectory.hpp"
-#include "rcutils/cmdline_parser.h"
-#include "sensor_msgs/msg/joint_state.hpp"
-
-#include
-#include
-
-ros::Publisher pub_joint_state_ros1;
-std::vector::SharedPtr> list_pub_trajectory;
-std::vector::SharedPtr> pub_ros2_lista;
-
-void motorStateCallback(const control_msgs::msg::JointTrajectoryControllerState::SharedPtr ros2_msg)
-{
-
- sensor_msgs::JointState ros1_joint_state_msg;
- ros1_joint_state_msg.header.stamp = ros::Time::now();
-
- ros1_joint_state_msg.name.resize(ros2_msg->joint_names.size());
- for(unsigned int i = 0; i < ros2_msg->joint_names.size(); i++){
- ros1_joint_state_msg.name[i] = "motor" + std::to_string(i+1);//ros2_msg->joint_names[i];
- }
-
- ros1_joint_state_msg.position.resize(ros2_msg->actual.positions.size());
- for(unsigned int j = 0; j < ros1_joint_state_msg.position.size(); j++){
- ros1_joint_state_msg.position[j] = ros2_msg->actual.positions[j];
- }
-
- ros1_joint_state_msg.velocity.resize(ros2_msg->actual.velocities.size());
- for(unsigned int j = 0; j < ros1_joint_state_msg.velocity.size(); j++){
- ros1_joint_state_msg.velocity[j] = ros2_msg->actual.velocities[j];
- }
-
- ros1_joint_state_msg.effort.resize(ros2_msg->actual.effort.size());
- for(unsigned int j = 0; j < ros1_joint_state_msg.effort.size(); j++){
- ros1_joint_state_msg.effort[j] = ros2_msg->actual.effort[j];
- }
-
- pub_joint_state_ros1.publish(ros1_joint_state_msg);
-}
-
-int main(int argc, char * argv[])
-{
-
- char hostname[150];
- memset(hostname, 0, 150);
- if(gethostname(hostname, 150)==-1){
- return -2;
- }
-
- std::string node_name = std::string("bridge");
- std::replace(node_name.begin(), node_name.end(), '-', '_');
-
- // ROS 1 node and publisher
- ros::init(argc, argv, "mara_bridge");
- ros::NodeHandle ros1_node;
-
- std::string file_motors;
- if (rcutils_cli_option_exist(argv, argv + argc, "-motors")){
- file_motors = std::string(rcutils_cli_get_option(argv, argv + argc, "-motors"));
- }
-
- std::cout << "Trying to open " << file_motors << std::endl;
-
- YAML::Node config = YAML::LoadFile(file_motors);
- if(config.IsNull()){
- std::cout << "return";
- return -1;
- }
- std::cout << config.size() << std::endl;
-
- std::vector lista_subscribers;
-
- for (auto motor : config["motors"]) {
- std::string s = motor.as();
- lista_subscribers.push_back(s);
- }
-
- pub_ros2_lista.resize(lista_subscribers.size());
- for (unsigned int j = 0; j < lista_subscribers.size(); j++){
- pub_ros2_lista[j] = NULL;
- }
-
- std::vector lista_subscribers_ros1;
-
- for(unsigned int i = 0; i < lista_subscribers.size(); i++){
-
- rclcpp::Publisher::SharedPtr pub_ros2 = pub_ros2_lista[i];
-
- std::cout << "Creating ROS 1 subscriber " << lista_subscribers[i] << "!" << std::endl;
-
- boost::function callback =
- [i] (const trajectory_msgs::JointTrajectory& ros1_msg) {
- auto ros2_msg = std::make_shared();
-
- ros2_msg->points.resize(ros1_msg.points.size());
- for (unsigned int i = 0; i < ros1_msg.points.size(); i++){
- ros2_msg->points[i].positions.resize(ros1_msg.points[i].positions.size());
- for (unsigned int j = 0; j < ros1_msg.points[i].positions.size(); j++ )
- ros2_msg->points[i].positions[j] = ros1_msg.points[i].positions[j];
-
- ros2_msg->points[i].velocities.resize(ros1_msg.points[i].velocities.size());
- for (unsigned int j = 0; j < ros1_msg.points[i].velocities.size(); j++ )
- ros2_msg->points[i].velocities[j] = ros1_msg.points[i].velocities[j];
-
- ros2_msg->points[i].accelerations.resize(ros1_msg.points[i].accelerations.size());
- for (unsigned int j = 0; j < ros1_msg.points[i].accelerations.size(); j++ )
- ros2_msg->points[i].accelerations[j] = ros1_msg.points[i].accelerations[j];
-
- ros2_msg->points[i].time_from_start.sec = ros1_msg.points[i].time_from_start.sec;
- ros2_msg->points[i].time_from_start.nanosec = ros1_msg.points[i].time_from_start.nsec;
- }
- if(pub_ros2_lista[i]!=NULL)
- pub_ros2_lista[i]->publish(ros2_msg);
- // std::cout << "publish!! " << i << pub_ros2_lista[i]->get_topic_name() << std::endl;
- };
- lista_subscribers_ros1.push_back(ros1_node.subscribe(lista_subscribers[i].c_str(), 1, callback));
- }
- pub_joint_state_ros1 = ros1_node.advertise("/joint_states", 10);
-
- // ROS 2 node and subscriber
- rclcpp::init(argc, argv);
- auto ros2_node = rclcpp::Node::make_shared("mara_bridge");
-
- for(unsigned int i = 0; i < lista_subscribers.size(); i++){
- std::cout << "Creating ROS 2 publisher " << lista_subscribers[i] << "!" << std::endl;
-
- pub_ros2_lista[i] =
- ros2_node->create_publisher
- (lista_subscribers[i], rmw_qos_profile_sensor_data);
- }
-
- auto sub_servoMotorGoal = ros2_node->create_subscription(
- "/mara_controller/state", motorStateCallback, rmw_qos_profile_sensor_data);
-
- //////////////////////////////////////////////////////////////////////////7
- // ROS 1 asynchronous spinner
- ros::AsyncSpinner async_spinner(1);
- async_spinner.start();
-
- // ROS 2 spinning loop
- rclcpp::executors::MultiThreadedExecutor executor;
- while (ros1_node.ok() && rclcpp::ok()) {
- executor.spin_node_once(ros2_node, std::chrono::milliseconds(100));
- }
-
- return 0;
-}
diff --git a/individual_trajectories_bridge/src/main_actions.cpp b/individual_trajectories_bridge/src/main_actions.cpp
index 7b8615a..08396a7 100644
--- a/individual_trajectories_bridge/src/main_actions.cpp
+++ b/individual_trajectories_bridge/src/main_actions.cpp
@@ -3,6 +3,8 @@
ros::Publisher pub_joint_state_ros1;
std::vector::SharedPtr> list_pub_trajectory;
std::vector::SharedPtr> pub_ros2_lista;
+std::string environment;
+std::string motor_key;
void motorStateCallback(const control_msgs::msg::JointTrajectoryControllerState::SharedPtr ros2_msg)
{
@@ -29,7 +31,7 @@ void motorStateCallback(const control_msgs::msg::JointTrajectoryControllerState:
for(unsigned int j = 0; j < ros1_joint_state_msg.effort.size(); j++){
ros1_joint_state_msg.effort[j] = ros2_msg->actual.effort[j];
}
-
+
pub_joint_state_ros1.publish(ros1_joint_state_msg);
}
@@ -65,7 +67,13 @@ int main(int argc, char * argv[])
std::vector lista_subscribers;
- for (auto motor : config["motors"]) {
+ environment = argv[3];
+ if (environment == "sim")
+ motor_key = "simulated_motors";
+ else if (environment == "real")
+ motor_key = "real_motors";
+
+ for (auto motor : config[motor_key]) {
std::string s = motor.as();
lista_subscribers.push_back(s);
}
diff --git a/mara_bringup/launch/mara.launch.py b/mara_bringup/launch/mara.launch.py
index 7900367..c85033d 100644
--- a/mara_bringup/launch/mara.launch.py
+++ b/mara_bringup/launch/mara.launch.py
@@ -35,7 +35,6 @@ def generate_launch_description():
ld = LaunchDescription([
Node(package='robot_state_publisher', node_executable='robot_state_publisher', output='screen', arguments=[urdf]),
- Node(package='hros_cognition_mara_components', node_executable='hros_cognition_mara_components', output='screen',
- arguments=["-motors", install_dir + "/share/hros_cognition_mara_components/link_order.yaml"])
+ Node(package='hros_cognition_mara_components', node_executable='hros_cognition_mara_components', output='screen', arguments=["-motors", install_dir + "/share/hros_cognition_mara_components/motors.yaml", "real"])
])
return ld
diff --git a/mara_gazebo/launch/mara.launch.py b/mara_gazebo/launch/mara.launch.py
index 12ac494..94c9f7a 100644
--- a/mara_gazebo/launch/mara.launch.py
+++ b/mara_gazebo/launch/mara.launch.py
@@ -48,7 +48,6 @@ def generate_launch_description():
),
Node(package='robot_state_publisher', node_executable='robot_state_publisher', output='screen', arguments=[urdf]),
Node(package='mara_utils_scripts', node_executable='spawn_mara.py', arguments=[urdf], output='screen'),
- Node(package='hros_cognition_mara_components', node_executable='hros_cognition_mara_components', output='screen',
- arguments=["-motors", install_dir + "/share/hros_cognition_mara_components/link_order.yaml"])
+ Node(package='hros_cognition_mara_components', node_executable='hros_cognition_mara_components', output='screen', arguments=["-motors", install_dir + "/share/hros_cognition_mara_components/motors.yaml", "sim"])
])
return ld
diff --git a/mara_gazebo/launch/mara_with_moveit_bridge.launch.py b/mara_gazebo/launch/mara_with_moveit_bridge.launch.py
index 3dc9256..60a604e 100644
--- a/mara_gazebo/launch/mara_with_moveit_bridge.launch.py
+++ b/mara_gazebo/launch/mara_with_moveit_bridge.launch.py
@@ -36,15 +36,10 @@ def generate_launch_description():
return None
ld = LaunchDescription([
- ExecuteProcess(
- cmd=['gazebo', '--verbose', '-s', 'libgazebo_ros_factory.so'], output='screen',
- env=envs
- ),
+ ExecuteProcess(cmd=['gazebo', '--verbose', '-s', 'libgazebo_ros_factory.so'], output='screen', env=envs),
Node(package='robot_state_publisher', node_executable='robot_state_publisher', output='screen', arguments=[urdf]),
Node(package='mara_utils_scripts', node_executable='spawn_entity.py', output='screen'),
- Node(package='hros_cognition_mara_components', node_executable='hros_cognition_mara_components', output='screen',
- arguments=["-motors", install_dir + "/share/hros_cognition_mara_components/link_order.yaml"]),
- Node(package='individual_trajectories_bridge', node_executable='individual_trajectories_bridge', output='screen',
- arguments=["-motors", install_dir + "/share/individual_trajectories_bridge/motors.yaml"])
+ Node(package='hros_cognition_mara_components', node_executable='hros_cognition_mara_components', output='screen', arguments=["-motors", install_dir + "/share/hros_cognition_mara_components/motors.yaml" "sim"]),
+ Node(package='individual_trajectories_bridge', node_executable='individual_trajectories_bridge', output='screen', arguments=["-motors", install_dir + "/share/hros_cognition_mara_components/motors.yaml" "sim"])
])
return ld