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
Showing
with 284 additions and 193 deletions
<launch>
<!-- Sot Controller configuration -->
<rosparam command="load" file="$(find talos_roscontrol_sot_talos)/config/sot_talos_params_gazebo_effort.yaml"/>
<rosparam command="load" file="$(find roscontrol_sot_talos)/config/sot_talos_params_gazebo_effort.yaml"/>
<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 talos_roscontrol_sot_talos)/config/sot_talos_controller.yaml" />
<rosparam command="load" file="$(find roscontrol_sot_talos)/config/sot_talos_controller.yaml" />
<!-- Spawn sot controller -->
<node name="sot_controller_spawner"
pkg="talos_controller_manager" type="spawner" output="screen"
pkg="controller_manager" type="spawner" output="screen"
args="sot_controller" />
</launch>
<?xml version="1.0"?>
<package>
<name>talos_roscontrol_sot_talos</name>
<version>0.0.7</version>
<name>roscontrol_sot_talos</name>
<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>
......@@ -42,6 +42,8 @@
<build_depend>realtime_tools</build_depend>
<build_depend>cmake_modules</build_depend>
<build_depend>roscontrol_sot</build_depend>
<build_depend>controller_interface</build_depend>
<build_depend>sot-talos</build_depend>
<run_depend>roscpp</run_depend>
<run_depend>control_msgs</run_depend>
......@@ -51,5 +53,7 @@
<run_depend>std_msgs</run_depend>
<run_depend>cmake_modules</run_depend>
<run_depend>roscontrol_sot</run_depend>
<run_depend>controller_interface</run_depend>
<run_depend>sot-talos</run_depend>
<!-- The export tag contains other, unspecified, tags -->
</package>
#!/usr/bin/env python
# license removed for brevity
import rospy
import tf
from dynamic_graph_bridge_msgs.msg import Vector
from sensor_msgs.msg import JointState
import sys
# Arg 1
input_topic = "/robotState"
# Arg 2
output_topic = "/sot/joint_state"
# Arg 3
publish_root_wrt_odom = False
if len(sys.argv) > 1:
input_topic = sys.argv[1]
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")
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] + "/"
else:
output_prefix = ""
rospy.loginfo(
"Will publish "
+ output_prefix
+ "base_link with respect to "
+ output_prefix
+ "odom"
)
jointnames = rospy.get_param("/sot_controller/joint_names")
def jointreceived(jstates):
global seqnb
seqnb = seqnb + 1
time = rospy.Time.now()
aJS.header.seq = seqnb
aJS.header.stamp = time
aJS.header.frame_id = "base_link"
aJS.name = jointnames
aJS.position = jstates.data[6:]
aJS.velocity = []
aJS.effort = []
pub.publish(aJS)
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",
)
def listener():
rospy.Subscriber(input_topic, Vector, jointreceived)
rospy.spin()
if __name__ == "__main__":
try:
listener()
except rospy.ROSInterruptException:
pass
#!/usr/bin/env python
# O. Stasse 17/01/2020
# LAAS, CNRS
import rospy
import time
import roslaunch
import rospkg
from std_srvs.srv import Empty
# Start roscore
import subprocess
roscore = subprocess.Popen("roscore")
time.sleep(1)
# Get the path to talos_data
arospack = rospkg.RosPack()
talos_data_path = arospack.get_path("talos_data")
# Start talos_gazebo
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",
]
roslaunch_args = cli_args[1:]
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()
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.start()
# 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()
# Start roscontrol
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"]
)
launch_roscontrol_sot_talos.start()
rospy.loginfo("roscontrol_sot_talos started")
rospy.spin()
#!/usr/bin/env python2.7
# 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").
import rospy
import time
import roslaunch
from std_srvs.srv import Empty
# Start roscore
import subprocess
roscore = subprocess.Popen("roscore")
time.sleep(1)
# Start talos_gazebo
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.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()
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.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()
# Start roscontrol
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.
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,22 +4,21 @@
<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="" />
<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)"
args=" --input-file $(arg libsot)"
launch-prefix="$(arg sot-launch-prefix)"
respawn="true">
<param name="/sot/dg/geometric_simu" value="" />
......
......@@ -4,22 +4,21 @@
<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" />
<!-- BTW we are in simulation ? -->
<!-- Load robot model. -->
<param name="robot_description"
textfile="$(find talos_data)/urdf/talos_reduced.urdf" />
textfile="$(find talos_data)/urdf/pyrene.urdf" />
<!-- Load robot sot params. -->
<rosparam command="load"
file="$(find sot_pyrene_bringup)/sot/pyrene.yaml" />
<machine name="geometric_simu_machine"
address="localhost">
</machine >
address="localhost" />
<!--
Read joint_states topic and publish link positions to tf.
......@@ -30,7 +29,7 @@
-->
<node name="robot_state_publisher"
pkg="robot_state_publisher"
type="state_publisher"
type="robot_state_publisher"
respawn="true">
<param name="tf_prefix" value="" />
</node>
......
<package>
<name>sot_pyrene_bringup</name>
<version>0.0.7</version>
<version>0.3.1</version>
<description>ROS package for Stack of Tasks on Pyrene</description>
<maintainer email="ostasse@laas.fr">Olivier Stasse</maintainer>
......
sot:
state_vector_map: [leg_left_1_joint, leg_left_2_joint, leg_left_3_joint, leg_left_4_joint, leg_left_5_joint, leg_left_6_joint,
leg_right_1_joint, leg_right_2_joint, leg_right_3_joint, leg_right_4_joint, leg_right_5_joint, leg_right_6_joint,
state_vector_map: [leg_left_1_joint, leg_left_2_joint, leg_left_3_joint, leg_left_4_joint, leg_left_5_joint, leg_left_6_joint,
leg_right_1_joint, leg_right_2_joint, leg_right_3_joint, leg_right_4_joint, leg_right_5_joint, leg_right_6_joint,
torso_1_joint, torso_2_joint,
arm_left_1_joint, arm_left_2_joint, arm_left_3_joint, arm_left_4_joint, arm_left_5_joint, arm_left_6_joint, arm_left_7_joint, gripper_left_joint,
arm_right_1_joint, arm_right_2_joint, arm_right_3_joint, arm_right_4_joint, arm_right_5_joint, arm_right_6_joint, arm_right_7_joint, gripper_right_joint,
......@@ -18,4 +18,10 @@ sot:
gripper_right_inner_single_joint: -gripper_right_joint,
gripper_right_fingertip_3_joint: -gripper_right_joint}
sot_controller:
joint_names: [ leg_left_1_joint, leg_left_2_joint, leg_left_3_joint, leg_left_4_joint, leg_left_5_joint, leg_left_6_joint,
leg_right_1_joint, leg_right_2_joint, leg_right_3_joint, leg_right_4_joint, leg_right_5_joint, leg_right_6_joint,
torso_1_joint,torso_2_joint,
arm_left_1_joint, arm_left_2_joint, arm_left_3_joint, arm_left_4_joint, arm_left_5_joint, arm_left_6_joint, arm_left_7_joint, gripper_left_joint,
arm_right_1_joint, arm_right_2_joint, arm_right_3_joint, arm_right_4_joint, arm_right_5_joint, arm_right_6_joint, arm_right_7_joint, gripper_right_joint, head_1_joint, head_2_joint
]
dt: 0.001
<package>
<name>talos_metapkg_ros_control_sot</name>
<version>0.0.7</version>
<version>0.3.1</version>
<description>A set of packages that include sot-wrapper and talos sot params .</description>
<maintainer email="olivier.stasse@laas.fr">Olivier Stasse</maintainer>
<license>BSD</license>
<url type="repository">https://github.com/stack-of-tasks/roscontrol_sot</url>
<url type="repository">https://github.com/stack-of-tasks/talos_metapkg_roscontrol_sot</url>
<author>Olivier Stasse</author>
<buildtool_depend>catkin</buildtool_depend>
<run_depend>talos_roscontrol_sot</run_depend>
<run_depend>talos_roscontrol_sot_talos</run_depend>
<run_depend>roscontrol_sot</run_depend>
<run_depend>roscontrol_sot_talos</run_depend>
<run_depend>realtime_tools</run_depend>
<run_depend>control_toolbox</run_depend>
......
cmake_minimum_required(VERSION 2.8.3)
project(talos_roscontrol_sot_talos)
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
dynamic_graph_bridge
control_msgs
sensor_msgs
realtime_tools
controller_interface
)
include_directories(include ${bullet_INCLUDE_DIRS} ${catkin_INCLUDE_DIRS})
link_directories(${bullet_LIBRARY_DIRS})
catkin_package()
###########
## Build ##
###########
## Specify additional locations of header files
## Your package locations should be listed before other locations
# include_directories(include)
include_directories(
${catkin_INCLUDE_DIRS}
)
## Add cmake target dependencies of the executable
## same as for the library above
# add_dependencies(roscontrol_sot_talos_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
#############
## Install ##
#############
# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# install(PROGRAMS
# scripts/my_python_script
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark executables and/or libraries for installation
foreach(dir config launch)
install(DIRECTORY ${dir}
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)
endforeach()
#############
## Testing ##
#############
## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_roscontrol_sot_talos.cpp)
# if(TARGET ${PROJECT_NAME}-test)
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()
## Add folders to be run by python nosetests
# catkin_add_nosetests(test)
sot_controller:
libname: libsot-pyrene-controller.so
joint_names: [ leg_left_1_joint, leg_left_2_joint, leg_left_3_joint, leg_left_4_joint, leg_left_5_joint, leg_left_6_joint,
leg_right_1_joint, leg_right_2_joint, leg_right_3_joint, leg_right_4_joint, leg_right_5_joint, leg_right_6_joint,
torso_1_joint,torso_2_joint,head_1_joint, head_2_joint,
arm_left_1_joint, arm_left_2_joint, arm_left_3_joint, arm_left_4_joint, arm_left_5_joint, arm_left_6_joint, arm_left_7_joint, gripper_left_joint,
arm_right_1_joint, arm_right_2_joint, arm_right_3_joint, arm_right_4_joint, arm_right_5_joint, arm_right_6_joint, arm_right_7_joint, gripper_right_joint
]
map_rc_to_sot_device: { motor-angles: motor-angles ,
joint-angles: joint-angles, velocities: velocities,
torques: torques, cmd-positions: control, cmd-effort: control }
control_mode: POSITION
dt: 0.001
sot_controller:
libname: libsot-pyrene-controller.so
simulation_mode: gazebo
joint_names: [ leg_left_1_joint, leg_left_2_joint, leg_left_3_joint, leg_left_4_joint, leg_left_5_joint, leg_left_6_joint,
leg_right_1_joint, leg_right_2_joint, leg_right_3_joint, leg_right_4_joint, leg_right_5_joint, leg_right_6_joint,
torso_1_joint,torso_2_joint,
arm_left_1_joint, arm_left_2_joint, arm_left_3_joint, arm_left_4_joint, arm_left_5_joint, arm_left_6_joint, arm_left_7_joint, gripper_left_joint,
arm_right_1_joint, arm_right_2_joint, arm_right_3_joint, arm_right_4_joint, arm_right_5_joint, arm_right_6_joint, arm_right_7_joint, gripper_right_joint,
head_1_joint, head_2_joint ]
map_rc_to_sot_device: { motor-angles: motor-angles ,
joint-angles: joint-angles, velocities: velocities,
torques: torques, cmd-joints: control, cmd-effort: control }
control_mode: POSITION
dt: 0.001
\ No newline at end of file
#!/usr/bin/env python
# license removed for brevity
import rospy
from dynamic_graph_bridge_msgs.msg import Vector
from sensor_msgs.msg import JointState
rospy.init_node('sot_reemitter', anonymous=True)
pub = rospy.Publisher('/sot/joint_state', String, queue_size=10)
aJS = JointState()
def jointreceived(jstates):
aJS.header.seq = seqnb
pub.publish(hello_str)
seqnb = seqnb+1
seqnb.stamp = ros::Time::now()
seqnb.frameid = "base_link"
seqnb.name = "joint_state"
seqnb.position = jstates.data[6:]
seqnb.velocity = []
seqnb.effort = []
def listener():
rospy.Subscriber("/sot_hpp/state", Vector, jointreceived)
ros.spin()
if __name__ == '__main__':
try:
listener()
except rospy.ROSInterruptException:
pass