Added rbs_gym package for RL & multi-robot launch setup
This commit is contained in:
parent
f92670cd0d
commit
b58307dea1
103 changed files with 15170 additions and 653 deletions
|
@ -26,6 +26,10 @@ def launch_setup(context, *args, **kwargs):
|
|||
"rbs_skill_servers", "config/gripperPositions.yaml"
|
||||
)
|
||||
|
||||
kinematics_yaml = load_yaml("rbs_arm", "config/kinematics.yaml")
|
||||
|
||||
robot_description_kinematics = {"robot_description_kinematics": kinematics_yaml}
|
||||
|
||||
move_topose_action_server = Node(
|
||||
package="rbs_skill_servers",
|
||||
executable="move_topose_action_server",
|
||||
|
@ -38,12 +42,6 @@ def launch_setup(context, *args, **kwargs):
|
|||
]
|
||||
)
|
||||
|
||||
move_to_pose = Node(
|
||||
package="rbs_skill_servers",
|
||||
executable="move_to_pose.py",
|
||||
namespace=namespace
|
||||
)
|
||||
|
||||
gripper_control_node = Node(
|
||||
package="rbs_skill_servers",
|
||||
executable="gripper_control_action_server",
|
||||
|
@ -68,9 +66,17 @@ def launch_setup(context, *args, **kwargs):
|
|||
{"use_sim_time": use_sim_time},
|
||||
]
|
||||
)
|
||||
|
||||
cartesian_move_to_pose_action_server = Node(
|
||||
package="rbs_skill_servers",
|
||||
executable="move_to_pose.py",
|
||||
namespace=namespace,
|
||||
parameters=[
|
||||
{"use_sim_time": use_sim_time},
|
||||
{"robot_name": namespace}
|
||||
]
|
||||
)
|
||||
|
||||
# FIXME: The name of this node, "move_topose,"
|
||||
# is intended to be different from the actual MoveToPose node.
|
||||
move_joint_state_action_server = Node(
|
||||
package="rbs_skill_servers",
|
||||
executable="move_to_joint_states_action_server",
|
||||
|
@ -95,7 +101,7 @@ def launch_setup(context, *args, **kwargs):
|
|||
gripper_control_node,
|
||||
move_cartesian_path_action_server,
|
||||
move_joint_state_action_server,
|
||||
move_to_pose,
|
||||
cartesian_move_to_pose_action_server,
|
||||
# grasp_pose_loader
|
||||
]
|
||||
return nodes_to_start
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue