Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found

Target

Select target project
  • gsaurel/talos-metapkg-ros-control-sot
  • stack-of-tasks/talos-metapkg-ros-control-sot
2 results
Show changes
Commits on Source (12)
Showing
with 201 additions and 155 deletions
# format (Guilhem Saurel, 2022-09-12)
22bb5a0457fa244d13386673401469c00ad7a043
include: http://rainboard.laas.fr/project/talos_metapkg_ros_control_sot/.gitlab-ci.yml
include: https://rainboard.laas.fr/project/talos-metapkg-ros-control-sot/.gitlab-ci.yml
ci:
autoupdate_branch: 'devel'
repos:
- repo: https://github.com/pre-commit/mirrors-clang-format
rev: v14.0.6
hooks:
- id: clang-format
args: [--style=Google]
- repo: https://github.com/pre-commit/pre-commit-hooks
rev: v4.3.0
hooks:
- id: check-added-large-files
- id: check-ast
- id: check-executables-have-shebangs
- id: check-json
- id: check-merge-conflict
- id: check-symlinks
- id: check-toml
- id: check-yaml
- id: debug-statements
- id: destroyed-symlinks
- id: detect-private-key
- id: end-of-file-fixer
- id: fix-byte-order-marker
- id: mixed-line-ending
- id: trailing-whitespace
- repo: https://github.com/psf/black
rev: 22.8.0
hooks:
- id: black
- repo: https://github.com/PyCQA/flake8
rev: 5.0.4
hooks:
- id: flake8
- repo: https://github.com/cheshirekow/cmake-format-precommit
rev: v0.6.13
hooks:
- id: cmake-format
This metapackage allows starting the stack of tasks for TALOS.
[![Pipeline status](https://gitlab.laas.fr/stack-of-tasks/talos-metapkg-ros-control-sot/badges/master/pipeline.svg)](https://gitlab.laas.fr/stack-of-tasks/talos-metapkg-ros-control-sot/commits/master)
[![Coverage report](https://gitlab.laas.fr/stack-of-tasks/talos-metapkg-ros-control-sot/badges/master/coverage.svg?job=doc-coverage)](https://gepettoweb.laas.fr/doc/stack-of-tasks/talos-metapkg-ros-control-sot/master/coverage/)
[![Code style: black](https://img.shields.io/badge/code%20style-black-000000.svg)](https://github.com/psf/black)
[![pre-commit.ci status](https://results.pre-commit.ci/badge/github/stack-of-tasks/talos-metapkg-ros-control-sot/master.svg)](https://results.pre-commit.ci/latest/github/stack-of-tasks/talos-metapkg-ros-control-sot)
## Introduction
Two methods to use the SoT with TALOS are possible:
......@@ -7,13 +12,13 @@ Two methods to use the SoT with TALOS are possible:
1. One based on roscontrol_sot which is using the roscontrol interface. The SoT is then acting as a Controller object interacting with the hardware interface. This is was is used with Gazebo and on the real robot.
2. One based on geometric-simu. This software is simply a taking the control provided by the SoT and integrates it using a Euler scheme. The order of integration is chosen automatically according to the control law.
## Using roscontrol_sot
## Using roscontrol_sot
### On Gazebo
To start the SoT in position mode control:
roslaunch roscontrol_sot_talos sot_talos_controller_gazebo.launch
To start the SoT in effort mode control:
roslaunch roscontrol_sot_talos sot_talos_controller_gazebo_effort.launch
......@@ -22,7 +27,7 @@ To start the SoT in effort mode control:
To start the SoT in position mode control:
``
roslaunch roscontrol_sot_talos sot_talos_controller.launch
``
``
To start the SoT in effort mode control:
``
roslaunch roscontrol_sot_talos sot_talos_controller_effort.launch
......@@ -33,6 +38,3 @@ roslaunch roscontrol_sot_talos sot_talos_controller_effort.launch
``
roslaunch sot_pyrene_bringup geometric_simu.launch
``
[tool.black]
exclude = "cmake"
......@@ -6,18 +6,17 @@ find_package(PkgConfig REQUIRED)
set(bullet_FOUND 0)
pkg_check_modules(bullet REQUIRED bullet)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
control_msgs
sensor_msgs
realtime_tools
controller_interface
)
# Find catkin macros and libraries if COMPONENTS list like find_package(catkin
# REQUIRED COMPONENTS xyz) is used, also find other catkin packages
find_package(
catkin REQUIRED
COMPONENTS roscpp
rospy
std_msgs
control_msgs
sensor_msgs
realtime_tools
controller_interface)
include_directories(include ${bullet_INCLUDE_DIRS} ${catkin_INCLUDE_DIRS})
......@@ -25,31 +24,24 @@ link_directories(${bullet_LIBRARY_DIRS})
catkin_package()
###########
## Build ##
###########
# ##############################################################################
# Build ##
# ##############################################################################
## Specify additional locations of header files
## Your package locations should be listed before other locations
# include_directories(include)
include_directories(
${catkin_INCLUDE_DIRS}
)
# Specify additional locations of header files Your package locations should be
# listed before other locations include_directories(include)
include_directories(${catkin_INCLUDE_DIRS})
#############
## Install ##
#############
# ##############################################################################
# Install ##
# ##############################################################################
## Mark executables and/or libraries for installation
# Mark executables and/or libraries for installation
foreach(dir config launch)
install(DIRECTORY ${dir}
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)
install(DIRECTORY ${dir} DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
endforeach()
catkin_install_python(PROGRAMS
scripts/republish
scripts/start_talos_gazebo.py
scripts/start_talos_gazebo_16_04.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})
catkin_install_python(
PROGRAMS scripts/republish scripts/start_talos_gazebo.py
scripts/start_talos_gazebo_16_04.py DESTINATION
${CATKIN_PACKAGE_BIN_DESTINATION})
......@@ -69,11 +69,10 @@ sot_controller:
- name: arm_right_7_joint
des_pos: 0.1
- name: gripper_right_joint
des_pos: -0.005
des_pos: -0.005
- name: head_1_joint
des_pos: 0.0
- name: head_2_joint
des_pos: 0.0
des_pos: 0.0
dt: 0.001
jitter: 0.0004
subsampling: 2
......@@ -17,7 +17,7 @@ sot_controller:
gripper_left_joint: { ros_control_mode: POSITION, sot_control_mode: POSITION}
gripper_right_joint: { ros_control_mode: POSITION, sot_control_mode: POSITION}
head_1_joint: { ros_control_mode: POSITION, sot_control_mode: POSITION}
head_2_joint: { ros_control_mode: POSITION, sot_control_mode: POSITION}
head_2_joint: { ros_control_mode: POSITION, sot_control_mode: POSITION}
leg_left_1_joint: { ros_control_mode: POSITION, sot_control_mode: VELOCITY}
leg_left_2_joint: { ros_control_mode: POSITION, sot_control_mode: VELOCITY}
leg_left_3_joint: { ros_control_mode: POSITION, sot_control_mode: VELOCITY}
......@@ -31,4 +31,4 @@ sot_controller:
leg_right_5_joint: { ros_control_mode: POSITION, sot_control_mode: VELOCITY}
leg_right_6_joint: { ros_control_mode: POSITION, sot_control_mode: VELOCITY}
torso_1_joint: { ros_control_mode: POSITION, sot_control_mode: VELOCITY}
torso_2_joint: { ros_control_mode: POSITION, sot_control_mode: VELOCITY}
\ No newline at end of file
torso_2_joint: { ros_control_mode: POSITION, sot_control_mode: VELOCITY}
......@@ -17,7 +17,7 @@ sot_controller:
gripper_left_joint: { ros_control_mode: POSITION, sot_control_mode: POSITION}
gripper_right_joint: { ros_control_mode: POSITION, sot_control_mode: POSITION}
head_1_joint: { ros_control_mode: POSITION, sot_control_mode: POSITION}
head_2_joint: { ros_control_mode: POSITION, sot_control_mode: POSITION}
head_2_joint: { ros_control_mode: POSITION, sot_control_mode: POSITION}
leg_left_1_joint: { ros_control_mode: EFFORT, sot_control_mode: EFFORT}
leg_left_2_joint: { ros_control_mode: EFFORT, sot_control_mode: EFFORT}
leg_left_3_joint: { ros_control_mode: EFFORT, sot_control_mode: EFFORT}
......@@ -31,5 +31,4 @@ sot_controller:
leg_right_5_joint: { ros_control_mode: EFFORT, sot_control_mode: EFFORT}
leg_right_6_joint: { ros_control_mode: EFFORT, sot_control_mode: EFFORT}
torso_1_joint: { ros_control_mode: EFFORT, sot_control_mode: EFFORT}
torso_2_joint: { ros_control_mode: EFFORT, sot_control_mode: EFFORT}
\ No newline at end of file
torso_2_joint: { ros_control_mode: EFFORT, sot_control_mode: EFFORT}
......@@ -2,13 +2,12 @@
<!-- Sot Controller configuration -->
<rosparam command="load" file="$(find roscontrol_sot_talos)/config/sot_talos_params.yaml"/>
<rosparam command="load" file="$(find roscontrol_sot_talos)/config/sot_talos_params_control_mode.yaml"/>
<rosparam command="load" file="$(find roscontrol_sot_talos)/config/sot_talos_params_control_mode.yaml"/>
<rosparam command="load" file="$(find roscontrol_sot_talos)/config/sot_talos_controller.yaml" />
<!-- Spawn walking controller -->
<node name="sot_controller_spawner"
pkg="controller_manager" type="spawner" output="screen"
args="sot_controller" />
</launch>
......@@ -5,11 +5,10 @@
<rosparam command="load" file="$(find roscontrol_sot_talos)/config/sot_talos_params_control_mode_effort.yaml"/>
<rosparam command="load" ns="/sot_controller/effort_control_pd_motor_init" file="$(find roscontrol_sot_talos)/config/pids_effort.yaml"/>
<rosparam command="load" file="$(find roscontrol_sot_talos)/config/sot_talos_controller.yaml" />
<!-- Spawn walking controller -->
<node name="sot_controller_spawner"
pkg="controller_manager" type="spawner" output="screen"
args="sot_controller" />
</launch>
......@@ -4,11 +4,10 @@
<rosparam command="load" file="$(find roscontrol_sot_talos)/config/sot_talos_params_gazebo.yaml"/>
<rosparam command="load" file="$(find roscontrol_sot_talos)/config/sot_talos_controller.yaml" />
<rosparam command="load" file="$(find roscontrol_sot_talos)/config/sot_talos_params_control_mode.yaml"/>
<!-- Spawn walking controller -->
<node name="sot_controller_spawner"
pkg="controller_manager" type="spawner" output="screen"
args="sot_controller" />
</launch>
......@@ -5,11 +5,10 @@
<rosparam command="load" file="$(find roscontrol_sot_talos)/config/sot_talos_params_control_mode_effort.yaml"/>
<rosparam command="load" ns="/sot_controller/effort_control_pd_motor_init" file="$(find talos_hardware_gazebo)/config/pids.yaml"/>
<rosparam command="load" file="$(find roscontrol_sot_talos)/config/sot_talos_controller.yaml" />
<!-- Spawn sot controller -->
<node name="sot_controller_spawner"
pkg="controller_manager" type="spawner" output="screen"
args="sot_controller" />
</launch>
<?xml version="1.0"?>
<package>
<name>roscontrol_sot_talos</name>
<version>0.0.13</version>
<version>0.3.1</version>
<description>Wrapping Stack-of-tasks for Talos in ros-control</description>
<!-- Maintainer email -->
<!-- Maintainer email -->
<maintainer email="ostasse@laas.fr">Olivier Stasse</maintainer>
......
#!/usr/bin/env python
# license removed for brevity
import rospy, tf
import rospy
import tf
from dynamic_graph_bridge_msgs.msg import Vector
from sensor_msgs.msg import JointState
import sys
......@@ -11,31 +12,38 @@ input_topic = "/robotState"
output_topic = "/sot/joint_state"
# Arg 3
publish_root_wrt_odom = False
if len(sys.argv)>1:
if len(sys.argv) > 1:
input_topic = sys.argv[1]
if len(sys.argv)>2:
if len(sys.argv) > 2:
output_topic = sys.argv[2]
if len(sys.argv)>3:
publish_root_wrt_odom = (sys.argv[3].lower() in ("true","on"))
if len(sys.argv) > 3:
publish_root_wrt_odom = sys.argv[3].lower() in ("true", "on")
rospy.init_node('sot_reemitter', anonymous=True)
rospy.init_node("sot_reemitter", anonymous=True)
pub = rospy.Publisher(output_topic, JointState, queue_size=10)
seqnb = 0
aJS = JointState()
if publish_root_wrt_odom:
if output_topic.find('/') >= 0:
output_prefix = output_topic.rsplit('/',1)[0] + '/'
if output_topic.find("/") >= 0:
output_prefix = output_topic.rsplit("/", 1)[0] + "/"
else:
output_prefix = ""
rospy.loginfo("Will publish " + output_prefix + "base_link with respect to " + output_prefix + "odom")
rospy.loginfo(
"Will publish "
+ output_prefix
+ "base_link with respect to "
+ output_prefix
+ "odom"
)
jointnames = rospy.get_param("/sot_controller/joint_names")
jointnames = rospy.get_param("/sot_controller/joint_names")
def jointreceived(jstates):
global seqnb
seqnb = seqnb+1
seqnb = seqnb + 1
time = rospy.Time.now()
aJS.header.seq = seqnb
aJS.header.stamp = time
......@@ -48,18 +56,23 @@ def jointreceived(jstates):
if publish_root_wrt_odom and len(jstates.data) > 6:
br = tf.TransformBroadcaster()
br.sendTransform(jstates.data[0:3],
tf.transformations.quaternion_from_euler(
jstates.data[3], jstates.data[4], jstates.data[5]),
time,
output_prefix + "base_link",
output_prefix + "odom")
br.sendTransform(
jstates.data[0:3],
tf.transformations.quaternion_from_euler(
jstates.data[3], jstates.data[4], jstates.data[5]
),
time,
output_prefix + "base_link",
output_prefix + "odom",
)
def listener():
rospy.Subscriber(input_topic, Vector, jointreceived)
rospy.spin()
if __name__ == '__main__':
if __name__ == "__main__":
try:
listener()
except rospy.ROSInterruptException:
......
......@@ -2,7 +2,6 @@
# O. Stasse 17/01/2020
# LAAS, CNRS
import os
import rospy
import time
import roslaunch
......@@ -12,59 +11,66 @@ from std_srvs.srv import Empty
# Start roscore
import subprocess
roscore = subprocess.Popen('roscore')
roscore = subprocess.Popen("roscore")
time.sleep(1)
# Get the path to talos_data
arospack = rospkg.RosPack()
talos_data_path = arospack.get_path('talos_data')
talos_data_path = arospack.get_path("talos_data")
# Start talos_gazebo
rospy.init_node('starting_talos_gazebo', anonymous=True)
rospy.init_node("starting_talos_gazebo", anonymous=True)
uuid = roslaunch.rlutil.get_or_generate_uuid(None, False)
roslaunch.configure_logging(uuid)
cli_args = [talos_data_path+'/launch/talos_gazebo_alone.launch',
'world:=empty_forced',
'enable_leg_passive:=false'
]
cli_args = [
talos_data_path + "/launch/talos_gazebo_alone.launch",
"world:=empty_forced",
"enable_leg_passive:=false",
]
roslaunch_args = cli_args[1:]
roslaunch_file = [(roslaunch.rlutil.resolve_launch_arguments(cli_args)[0], roslaunch_args)]
roslaunch_file = [
(roslaunch.rlutil.resolve_launch_arguments(cli_args)[0], roslaunch_args)
]
launch_gazebo_alone = roslaunch.parent.ROSLaunchParent(uuid, roslaunch_file)
launch_gazebo_alone.start()
rospy.loginfo("talos_gazebo_alone started")
rospy.wait_for_service("/gazebo/pause_physics")
gazebo_pause_physics = rospy.ServiceProxy('/gazebo/pause_physics', Empty)
gazebo_pause_physics = rospy.ServiceProxy("/gazebo/pause_physics", Empty)
gazebo_pause_physics()
time.sleep(5)
# Spawn talos model in gazebo
launch_gazebo_spawn_hs = roslaunch.parent.ROSLaunchParent(uuid,
[talos_data_path+'/launch/talos_gazebo_spawn_hs.launch'])
#launch_gazebo_spawn_hs = roslaunch.parent.ROSLaunchParent(uuid,
# [talos_data_path+'/launch/talos_gazebo_spawn_hs_wide.launch'])
launch_gazebo_spawn_hs = roslaunch.parent.ROSLaunchParent(
uuid, [talos_data_path + "/launch/talos_gazebo_spawn_hs.launch"]
)
# launch_gazebo_spawn_hs = roslaunch.parent.ROSLaunchParent(
# uuid, [talos_data_path + "/launch/talos_gazebo_spawn_hs_wide.launch"]
# )
launch_gazebo_spawn_hs.start()
#rospy.loginfo("talos_gazebo_spawn_hs started")
# rospy.loginfo("talos_gazebo_spawn_hs started")
rospy.wait_for_service("/gains/arm_left_1_joint/set_parameters")
time.sleep(5)
gazebo_unpause_physics = rospy.ServiceProxy('/gazebo/unpause_physics', Empty)
gazebo_unpause_physics = rospy.ServiceProxy("/gazebo/unpause_physics", Empty)
gazebo_unpause_physics()
# Start roscontrol
launch_bringup = roslaunch.parent.ROSLaunchParent(uuid,
[talos_data_path+'/launch/talos_bringup.launch'])
launch_bringup = roslaunch.parent.ROSLaunchParent(
uuid, [talos_data_path + "/launch/talos_bringup.launch"]
)
launch_bringup.start()
rospy.loginfo("talos_bringup started")
# Start sot
roscontrol_sot_talos_path=arospack.get_path('roscontrol_sot_talos')
launch_roscontrol_sot_talos =roslaunch.parent.ROSLaunchParent(uuid,
[roscontrol_sot_talos_path+'/launch/sot_talos_controller_gazebo.launch'])
roscontrol_sot_talos_path = arospack.get_path("roscontrol_sot_talos")
launch_roscontrol_sot_talos = roslaunch.parent.ROSLaunchParent(
uuid, [roscontrol_sot_talos_path + "/launch/sot_talos_controller_gazebo.launch"]
)
launch_roscontrol_sot_talos.start()
rospy.loginfo("roscontrol_sot_talos started")
rospy.spin()
......@@ -2,11 +2,13 @@
# O. Stasse 17/01/2020
# LAAS, CNRS
# This file is a temporary fix for the ubuntu version 16.04 of the script start_talos_gazebo.py
# The path to talos_data cannot be retreive using the rospkg.RosPack() and get_path('talos_data') in 16.04.
# This should be investigated (see issue #4 "Hardcoded talos_data path for 16.04 in script start_talos_gazebo_16_04.py")
# This file is a temporary fix for the ubuntu version 16.04 of the script
# start_talos_gazebo.py.
# The path to talos_data cannot be retreive using the rospkg.RosPack() and
# get_path('talos_data') in 16.04.
# This should be investigated (see issue #4 "Hardcoded talos_data path for 16.04 in
# script start_talos_gazebo_16_04.py").
import os
import rospy
import time
import roslaunch
......@@ -14,42 +16,50 @@ from std_srvs.srv import Empty
# Start roscore
import subprocess
roscore = subprocess.Popen('roscore')
roscore = subprocess.Popen("roscore")
time.sleep(1)
# Start talos_gazebo
rospy.init_node('starting_talos_gazebo', anonymous=True)
rospy.init_node("starting_talos_gazebo", anonymous=True)
uuid = roslaunch.rlutil.get_or_generate_uuid(None, False)
roslaunch.configure_logging(uuid)
launch_gazebo_alone = roslaunch.parent.ROSLaunchParent(uuid, ["/opt/openrobots/share/talos_data/launch/talos_gazebo_alone.launch"])
launch_gazebo_alone = roslaunch.parent.ROSLaunchParent(
uuid, ["/opt/openrobots/share/talos_data/launch/talos_gazebo_alone.launch"]
)
launch_gazebo_alone.start()
rospy.loginfo("talos_gazebo_alone started")
rospy.wait_for_service("/gazebo/pause_physics")
gazebo_pause_physics = rospy.ServiceProxy('/gazebo/pause_physics', Empty)
gazebo_pause_physics = rospy.ServiceProxy("/gazebo/pause_physics", Empty)
gazebo_pause_physics()
time.sleep(3)
# Spawn talos model in gazebo
launch_gazebo_spawn_hs = roslaunch.parent.ROSLaunchParent(uuid, ["/opt/openrobots/share/talos_data/launch/talos_gazebo_spawn_hs.launch"])
launch_gazebo_spawn_hs = roslaunch.parent.ROSLaunchParent(
uuid, ["/opt/openrobots/share/talos_data/launch/talos_gazebo_spawn_hs.launch"]
)
launch_gazebo_spawn_hs.start()
rospy.loginfo("talos_gazebo_spawn_hs started")
rospy.wait_for_service("/gains/arm_left_1_joint/set_parameters")
time.sleep(3)
gazebo_unpause_physics = rospy.ServiceProxy('/gazebo/unpause_physics', Empty)
gazebo_unpause_physics = rospy.ServiceProxy("/gazebo/unpause_physics", Empty)
gazebo_unpause_physics()
# Start roscontrol
launch_bringup = roslaunch.parent.ROSLaunchParent(uuid, ["/opt/openrobots/share/talos_data/launch/talos_bringup.launch"])
launch_bringup = roslaunch.parent.ROSLaunchParent(
uuid, ["/opt/openrobots/share/talos_data/launch/talos_bringup.launch"]
)
launch_bringup.start()
rospy.loginfo("talos_bringup started")
# # Start sot
# Start sot in another terminal with "roslaunch roscontrol_sot_talos sot_talos_controller_gazebo.launch"
# in order to have the logs saved. Otherwise the data are not correctly dumped when the process is killed.
# Start sot in another terminal with "roslaunch roscontrol_sot_talos
# sot_talos_controller_gazebo.launch".
# in order to have the logs saved. Otherwise the data are not correctly dumped when the
# process is killed.
rospy.spin()
[flake8]
exclude = cmake
max-line-length = 88
extend-ignore = E203
......@@ -5,35 +5,19 @@ project(sot_pyrene_bringup)
find_package(catkin REQUIRED)
catkin_package()
#set(PROJECT_NAME sot_talos_bringup)
#set(PROJECT_DESCRIPTION ROS package for Stack of Tasks on Talos)
#set(PROJECT_URL "")
#setup_project()
INSTALL(
FILES
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config
)
INSTALL(
FILES
launch/geometric_simu.launch
launch/geometric_simu_context.launch
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch
)
INSTALL(
FILES
sot/pyrene.yaml
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/sot
)
INSTALL(
FILES
package.xml
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/
)
#setup_project_finalize()
# set(PROJECT_NAME sot_talos_bringup) set(PROJECT_DESCRIPTION ROS package for
# Stack of Tasks on Talos) set(PROJECT_URL "")
# setup_project()
install(FILES DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config)
install(FILES launch/geometric_simu.launch launch/geometric_simu_context.launch
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch)
install(FILES sot/pyrene.yaml
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/sot)
install(FILES package.xml DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/)
# setup_project_finalize()
......@@ -4,18 +4,18 @@
<launch>
<!-- Which robot are we controlling ? -->
<arg name="robot" default="pyrene" />
<arg name="libsot" default="libsot-pyrene-controller.so" />
<arg name="libsot" default="libsot-pyrene-controller.so" />
<arg name="sot-launch-prefix" default="" />
<include file="$(find sot_pyrene_bringup)/launch/geometric_simu_context.launch" >
<arg name="robot" value="$(arg robot)" />
<arg name="robot" value="$(arg robot)" />
<arg name="libsot" value="$(arg libsot)" />
</include>
<!-- Load Stack of Tasks. -->
<node machine="geometric_simu_machine"
name="node_stack_of_tasks"
<node machine="geometric_simu_machine"
name="node_stack_of_tasks"
pkg="dynamic_graph_bridge"
type="geometric_simu"
args=" --input-file $(arg libsot)"
......