Introduction
Supported Platforms
OS | Core | GUI | ROS | ROS2 |
---|---|---|---|---|
Linux (Ubuntu) | ✔ | ✔ | ✔ | ✔ |
MacOS | ✔ | ✔ | ✔ | |
Windows | ✔ | ✔ |
Ubuntu is supported as Linux. The approximate functionality is available even under MacOS and Windows.
It can be used without ROS installation even when using Linux or MacOS.
Installation for Rust
If you are new to Rust, please follow this to install Rust.
Installation for latest OpenRR
You can clone from GitHub.
git clone https://github.com/openrr/openrr
Installation for dependency
Install software dependencies. (For Linux user)
sudo apt install cmake build-essential libudev-dev xorg-dev libglu1-mesa-dev libasound2-dev libxkbcommon-dev
[Optional] Installation for ROS
arci-ros
- ROS Noetic
arci-ros2
Using OpenRR Apps
- Installation
- Operating robot from GUI
- Operating robot from CLI
- Robot teleoperation
- Operating mobile robot with ROS2 and openrr-teleop
- Operating robot arm with ROS/ROS2 and openrr-teleop
Installation
openrr-apps
allows you to operate a basic robot. It is one of the applications using OpenRR, a framework implemented in Rust.
urdf-viz
urdf-viz
is a URDF visualization application.
Actually, urdf-viz
is not part of OpenRR, but it is recommended to install because it is used frequently in this section.
cargo install urdf-viz
openrr-apps
openrr-apps
is an application that implements GUI, gamepad-based operations, etc. It can send commands, topics to ROS. Robots and real machines visualized by urdf-viz
and gazebo
can be operated in the same way.
git clone https://github.com/openrr/openrr
cd openrr
For Linux and MacOS users.
cargo install --path openrr-apps
For Windows users.
cargo install --path openrr-apps --no-default-features --features gui,assimp
Operating robot from GUI
Move the robot arm
If you have not cloned OpenRR
, do this.
git clone https://github.com:openrr/openrr
cd openrr
Let's display the sample robot arm.
urdf-viz ./openrr-planner/sample.urdf &
openrr_apps_joint_position_sender
openrr_apps_joint_position_sender \
--config-path ./openrr-apps/config/sample_robot_client_config_for_urdf_viz.toml
By sliding the bar, the joint angle of the robot arm can be specified.
Move the mobile robot
urdf-viz ./openrr-planner/sample.urdf &
openrr_apps_velocity_sender
openrr_apps_velocity_sender \
--config-path ./openrr-apps/config/sample_robot_client_config_for_urdf_viz.toml
By sliding the bar, you can specify the robot's velocity and angular velocity.
Operating robot from CLI
Move the robot arm
From the command text file
If you have not cloned OpenRR
, do this.
git clone https://github.com:openrr/openrr
cd openrr
Let's display the sample robot arm.
urdf-viz ./openrr-planner/sample.urdf &
You can use load_commands
to execute commands in a text file. Now, let's do it for the robot arm.
openrr_apps_robot_command \
--config-path ./openrr-apps/config/sample_robot_client_config_for_urdf_viz.toml \
load_commands ./openrr-apps/command/sample_cmd_urdf_viz.txt
Finally, if the terminal outputs the following, it is successful.
PrintSpeaker: "This is sample robot"
From your command line
It can also be executed by typing the command directly without using load_commands
. Try to get the robot arm status.
openrr_apps_robot_command \
--config-path ./openrr-apps/config/sample_robot_client_config_for_urdf_viz.toml \
get_state l_arm
The output will be as follows.
Joint names : ["l_shoulder_yaw", "l_shoulder_pitch", "l_shoulder_roll", "l_elbow_pitch", "l_wrist_yaw", "l_wrist_pitch"]
Joint positions : [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
Let's send the command value of the joint angle.
openrr_apps_robot_command \
--config-path ./openrr-apps/config/sample_robot_client_config_for_urdf_viz.toml \
send_joints l_arm -j 0=1.2 -j 1=-1.2 -j 2=0.0 -j 3=1.2 -j 4=0.0 -j 5=0.0
The robot arm moved.
Robot client config file
This is sample config file for single robot arm. Whether on a simulation or a real robot, operations from OpenRR can be realized by specifying the config file corresponding to the robot as shown below.
However, the urdf-viz
item, like [urdf_viz_clients_configs]
, must be changed to ROS or similar.
[[urdf_viz_clients_configs]]
name = "arm"
joint_names = [
"shoulder_yaw",
"shoulder_pitch",
"shoulder_roll",
"elbow_pitch",
"wrist_yaw",
"wrist_pitch",
]
wrap_with_joint_position_limiter = true
# If joint_position_limits is not specified, limits will be got from URDF.
# The following values are the same as if getting limits from URDF.
joint_position_limits = [
{ lower = -3.0, upper = 3.0 },
{ lower = -2.0, upper = 1.5 },
{ lower = -1.5, upper = 2.0 },
{ lower = -2.0, upper = 1.5 },
{ lower = -3.0, upper = 3.0 },
{ lower = -2.0, upper = 2.0 },
]
[openrr_clients_config]
urdf_path = "{path_to_urdf}/sample.urdf"
self_collision_check_pairs = ["shoulder_yaw:gripper_linear1"]
# Client config for left arm
[[openrr_clients_config.collision_check_clients_configs]]
name = "arm_collision_checked"
client_name = "arm"
[[openrr_clients_config.ik_clients_configs]]
name = "arm_ik"
client_name = "arm_collision_checked"
solver_name = "arm_ik_solver"
[[openrr_clients_config.joints_poses]]
pose_name = "zero"
client_name = "arm_collision_checked"
positions = [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
[openrr_clients_config.ik_solvers_configs.l_arm_ik_solver]
ik_target = "tool_fixed"
Note
See also reference of openrr_apps_robot_command
Robot teleoperation
When using openrr-teleop
, a configuration file must be created.
Move the robot arm and mobile robot
urdf-viz ./openrr-planner/sample.urdf &
openrr_apps_robot_teleop --config-path ./openrr-apps/config/sample_teleop_config_urdf_viz.toml
In base
mode, the robot itself moves, not the robot arm.
In the sample file, move_base_mode
is specified. This specifies the behavior of the robot as a mobile robot.
Teleop config
Client config file
This config file is the same as the "Operating robot from CLI"
one.
[[urdf_viz_clients_configs]]
name = "arm"
joint_names = [
"shoulder_yaw",
"shoulder_pitch",
"shoulder_roll",
"elbow_pitch",
"wrist_yaw",
"wrist_pitch",
]
wrap_with_joint_position_limiter = true
# If joint_position_limits is not specified, limits will be got from URDF.
# The following values are the same as if getting limits from URDF.
joint_position_limits = [
{ lower = -3.0, upper = 3.0 },
{ lower = -2.0, upper = 1.5 },
{ lower = -1.5, upper = 2.0 },
{ lower = -2.0, upper = 1.5 },
{ lower = -3.0, upper = 3.0 },
{ lower = -2.0, upper = 2.0 },
]
[openrr_clients_config]
urdf_path = "{path_to_urdf}/sample.urdf"
self_collision_check_pairs = ["shoulder_yaw:gripper_linear1"]
# Client config for left arm
[[openrr_clients_config.collision_check_clients_configs]]
name = "arm_collision_checked"
client_name = "arm"
[[openrr_clients_config.ik_clients_configs]]
name = "arm_ik"
client_name = "arm_collision_checked"
solver_name = "arm_ik_solver"
[[openrr_clients_config.joints_poses]]
pose_name = "zero"
client_name = "arm_collision_checked"
positions = [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
[openrr_clients_config.ik_solvers_configs.arm_ik_solver]
ik_target = "tool_fixed"
Teleop config file
Create a teleop config file as follows. If a teleop file is created, it must correspond to a client config file like first line.
robot_config_path = "sample_robot_client_config_for_urdf_viz.toml"
[control_nodes_config]
move_base_mode = "base"
[control_nodes_config.joints_pose_sender_config]
[[control_nodes_config.ik_node_teleop_configs]]
solver_name = "arm_ik_solver"
joint_trajectory_client_name = "arm"
[control_nodes_config.ik_node_teleop_configs.config]
mode = "i k"
[[control_nodes_config.joy_joint_teleop_configs]]
client_name = "arm_collision_checked"
[control_nodes_config.joy_joint_teleop_configs.config]
mode = "arm"
Note
See also reference of openrr_apps_robot__teleop
Operating mobile robot with ROS2 and openrr-teleop
Turtlebot3
move_base = "arci_ros2"
navigation = "arci_ros2"
[openrr_clients_config]
[plugins.arci_ros2]
path = "../../target/debug/libarci_ros2"
[[plugins.arci_ros2.instances]]
name = "arci_ros2"
type = "MoveBase"
args = """
topic = "/cmd_vel"
"""
[[plugins.arci_ros2.instances]]
name = "arci_ros2"
type = "Navigation"
args = """
action_name = "/navigate_to_pose"
"""
iRobot Create3
Same like Turtlebot3.
move_base = "arci_ros2"
[openrr_clients_config]
[plugins.arci_ros2]
path = "../../target/release/libarci_ros2"
[[plugins.arci_ros2.instances]]
name = "arci_ros2"
type = "MoveBase"
args = """
topic = "/cmd_vel"
"""
robot_config_path = "irobot_create_robot_client_config_ros2.toml"
initial_mode = "base"
[control_nodes_config]
move_base_mode = "base"
[[control_nodes_config.command_configs]]
name = "dock command"
file_path = "irobot_create_dock_command.txt"
[[control_nodes_config.command_configs]]
name = "undock command"
file_path = "irobot_create_undock_command.txt"
According to APIs page of Create Docs, the following commands allow you to command specific actions.
ros2 action send_goal /undock irobot_create_msgs/action/Undock "{}"
ros2 action send_goal /dock irobot_create_msgs/action/DockServo "{}"
openrr_apps_robot_commands execute_command -- <command>
- irobot_create_dock_command.txt
openrr_apps_robot_commands execute_command -- ros2 action send_goal /undock irobot_create_msgs/action/Undock "{}"
- irobot_create_undock_command.txt
openrr_apps_robot_commands execute_command -- ros2 action send_goal /dock irobot_create_msgs/action/DockServo "{}"
Operating robot arm with ROS/ROS2 and openrr-teleop
Ufactory Lite6 (ROS)
Setup
According to repository for xarm_ros
, you can set up a robotic arm for ROS
as follows.
mkdir -p ~/xarm_ws/src
cd ~/xarm_ws/src
git clone https://github.com/xArm-Developer/xarm_ros
cd xarm-ros
git pull
git submodule sync
git submodule update --init --remote
rosdep update
rosdep install --from-paths . --ignore-src --rosdistro noetic -y
cd ~/xarm_ws
catkin_make
Build OpenRR with Feature in ROS
.
cd openrr
cargo build --release --feature ros
cargo install --path ./openrr-apps
Config file for client
Specify joint names, topics, etc. for ROS in ros_clients_configs
.
It is also possible to name a specific posture and execute it. In this case, we will determine the initial posture and register it as initial_pose
.
- robot_client_for_ros.toml
[[ros_clients_configs]]
name = "lite6"
joint_names = ["joint1", "joint2", "joint3", "joint4", "joint5", "joint6"]
complete_allowable_errors = [0.02, 0.02, 0.02, 0.02, 0.02, 0.02]
controller_name = "/ufactory/lite6_traj_controller"
state_topic_name = "/ufactory/lite6_traj_controller/state"
[openrr_clients_config]
urdf_path = "$(rospack find xarm_description)/urdf/lite6_robot.urdf.xacro"
self_collision_check_pairs = ["joint1:joint4"]
[[openrr_clients_config.ik_clients_configs]]
name = "arm_ik"
client_name = "arm_collision_checked"
solver_name = "arm_ik_solver"
[openrr_clients_config.ik_solvers_configs.arm_ik_solver]
ik_target = "joint_eef"
[[openrr_clients_config.collision_check_clients_configs]]
name = "arm_collision_checked"
client_name = "lite6"
[[openrr_clients_config.joints_poses]]
pose_name = "zero"
client_name = "arm_collision_checked"
positions = [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
[[openrr_clients_config.joints_poses]]
pose_name = "initial_pose"
client_name = "arm_collision_checked"
positions = [0.0, 0.17, 0.56, 0.0, 0.38, 0.0]
Config file for teleop
- teleop_client_for_ros.toml
robot_config_path = "robot_client_config_for_ros.toml"
[control_nodes_config]
[control_nodes_config.joints_pose_sender_config]
[[control_nodes_config.ik_node_teleop_configs]]
solver_name = "arm_ik_solver"
joint_trajectory_client_name = "lite6"
[control_nodes_config.ik_node_teleop_configs.config]
mode = "i k"
[[control_nodes_config.joy_joint_teleop_configs]]
client_name = "arm_collision_checked"
[control_nodes_config.joy_joint_teleop_configs.config]
mode = "lite6"
Assigns the configured command to be executed.
- Command to be enable servo (enable_servo.txt)
openrr_apps_robot_commands execute_command -- rosservice call /ufactory/motion_ctrl 8 1
openrr_apps_robot_commands execute_command -- rosservice call /ufactory/set_mode 1
openrr_apps_robot_commands execute_command -- rosservice call /ufactory/set_state 0
openrr_apps_robot_command speak Default "Initialization completed!"
- Command for stop servo (stop_servo.txt)
openrr_apps_robot_commands execute_command -- rosservice call /ufactory/motion_ctrl 8 0
Then add the following to the teleop file you just created file (teleop_client_for_ros.toml).
...
[[control_nodes_config.command_configs]]
name = "stop servo"
file_path = "../command/stop_servo.txt"
[[control_nodes_config.command_configs]]
name = "enable servo"
file_path = "../command/enable_servo.txt"
Then, after enabling ROS, do the following two things.
roslaunch xarm_gazebo lite6_beside_table.launch
openrr_apps_robot_teleop --config-path ./config/teleop_config_for_ros.toml
If you have a Lite6
, below.
roslaunch lite6_moveit_config realMove_exec.launch robot_ip:=192.168.1.xxx
openrr_apps_robot_teleop --config-path ./config/teleop_config_for_ros.toml
Ufactory Lite6 (ROS2)
Setup
According to repository for xarm_ros2
, you can set up a robotic arm for ROS2
as follows.
mkdir -p ~/xarm_ws/src
cd ~/xarm_ws/src
git clone https://github.com/xArm-Developer/xarm_ros2
cd xarm-ros2
git pull
git submodule sync
git submodule update --init --remote
rosdep update
rosdep install --from-paths . --ignore-src --rosdistro $ROS_DISTRO -y
cd ~/xarm_ws
colcon build
Build OpenRR with Feature in ROS2
.
cd openrr
cargo build --release --feature ros2
cargo install --path ./openrr-apps
Config file for client
For ROS2, specify as a plugin.
[plugins.arci_ros2]
# Path to OpenRR
path = "../../openrr/target/release/libarci_ros2"
[[plugins.arci_ros2.instances]]
name = "lite6"
type = "JointTrajectoryClient"
args = """
action_name = "/lite6_traj_controller"
"""
[openrr_clients_config]
urdf_path = "../lite6_robot.urdf"
self_collision_check_pairs = ["joint1:joint4"]
[[openrr_clients_config.ik_clients_configs]]
name = "arm_ik"
client_name = "arm_collision_checked"
solver_name = "arm_ik_solver"
[openrr_clients_config.ik_solvers_configs.arm_ik_solver]
ik_target = "joint_eef"
[[openrr_clients_config.collision_check_clients_configs]]
name = "arm_collision_checked"
client_name = "lite6"
[[openrr_clients_config.joints_poses]]
pose_name = "zero"
client_name = "arm_collision_checked"
positions = [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
[[openrr_clients_config.joints_poses]]
pose_name = "initial_pose"
client_name = "arm_collision_checked"
positions = [0.0, 0.17, 0.56, 0.0, 0.38, 0.0]
Config file for teleop
The teleop config file is same as the ROS
one.
robot_config_path = "robot_client_config_for_ros2.toml"
[control_nodes_config]
joints_pose_sender_config.mode = "pose"
[[control_nodes_config.ik_node_teleop_configs]]
solver_name = "arm_ik_solver"
joint_trajectory_client_name = "lite6"
[control_nodes_config.ik_node_teleop_configs.config]
mode = "i k"
[[control_nodes_config.joy_joint_teleop_configs]]
client_name = "arm_collision_checked"
[control_nodes_config.joy_joint_teleop_configs.config]
mode = "lite6"
Note
See also xarm_ros and xarm_ros2, openrr-apps-ufactory-lite6
OpenRR Apps Usage
- openrr_apps_robot_command
- openrr_apps_robot_teleop
- openrr_apps_joint_position_sender
- openrr_apps_velocity_sender
openrr_apps_robot_command
The openrr_apps_robot_command
allows you to send several commands to the robot.
openrr_apps_robot_command [OPTIONS] [SUBCOMMAND]
Options | Description |
---|---|
-c, --config-path <CONFIG_PATH> | Path to the setting file |
--config <CONFIG> | Set options from command line. These settings take priority over the setting file specified by --config-path |
-h, --help | Print help information |
-i, --interactive | Use interactive mode |
--log-directory <LOG_DIRECTORY> | Path to log directory for tracing FileAppender |
--show-default-config | Prints the default setting as TOML |
Subcommands | Description |
---|---|
cancel_navigation_goal | Cancel navigation goal |
execute_command | Execute an external command |
get_navigation_current_pose | Get navigation current pose |
get_state | Get joint positions and end pose if applicable |
help | Print this message or the help of the given subcommand(s) |
list | List available clients |
load_commands | Load commands from file and execute them |
move_ik | Move with ik Usage of move_ik |
send_base_velocity | Send base velocity Usage of send_base_velocity |
send_joints | Send joint positions Usage of send_joints |
send_joints_pose | Send predefined joint positions Usage of send_joints_pose |
send_navigation_goal | Send navigation goal pose Usage of send_navigation_goal |
shell_completion | Shell completion Usage of shell_completion |
speak | Speak text message |
Example
Start the robot on the simulator.
urdf-viz ./openrr-planner/sample.urdf &
After that, load robot command.
openrr_apps_robot_command --config-path ./openrr-apps/config/sample_robot_client_config_for_urdf_viz.toml load_commands ./openrr-apps/command/sample_cmd_urdf_viz.txt
Example (--config)
Let's add a --config
argument to the previous example. You can watch it run on urdf-viz
, but for simplicity I have changed load_commands
to list
.
urdf-viz ./openrr-planner/sample.urdf &
openrr_apps_robot_command \
--config-path ./openrr-apps/config/sample_robot_client_config_for_urdf_viz.toml \
list
If you run it without doing anything first, you will get output like the first half of the previous section.
Raw joint trajectory clients
r_arm
l_arm
Joint trajectory clients
r_arm
r_arm_ik
l_arm_collision_checked
l_arm_ik
r_arm_collision_checked
l_arm
Collision check clients
l_arm_collision_checked
r_arm_collision_checked
Ik clients
r_arm_ik
l_arm_ik
The --config
argument can override the contents of --config-path
.
urdf-viz ./openrr-planner/sample.urdf &
openrr_apps_robot_command \
--config-path ./openrr-apps/config/sample_robot_client_config_for_urdf_viz.toml \
--config openrr_clients_config.ik_clients_configs[0].name=\"user_defined_ik\" \
list
When this command is executed, the output is as follows
Raw joint trajectory clients
l_arm
r_arm
Joint trajectory clients
l_arm
r_arm_collision_checked
l_arm_collision_checked
r_arm
r_arm_ik
user_defined_ik
Collision check clients
r_arm_collision_checked
l_arm_collision_checked
Ik clients
r_arm_ik
user_defined_ik
The IK client name for the left arm has been changed to user_defined_ik
. Of course this can also be accomplished by directly rewriting the toml file.
If you want to run it as load_commands
, you need to change l_arm_ik
to user_defined_ik
in openrr-apps/command/sample_cmd_urdf_viz.txt
.
Usage of move_ik
openrr_apps_robot_command move_ik [OPTIONS] <NAME>
Name
IK client name
Option
Options | Description |
---|---|
-d, --duration | |
-h, --help | Print help information |
-i, --interpolate | Interpolate target in cartesian space |
-l, --local | |
--max_resolution_for_interpolation <MAX_RESOLUTION_FOR_INTERPOLATION> | Max resolution for interpolation (default 0.5) |
--min_number_of_points_for_interpolation <MIN_NUMBER_OF_POINTS_FOR_INTERPOLATION> | Min number of points for interpolation (default 10) |
-r, --roll | Target roll |
-p, --pitch | Target pitch |
--yaw | Target yaw |
-x, --x | Target x coordinate |
-y, --y | Target y coordinate |
-z, --z | Target z coordinate |
Usage of send_base_velocity
openrr_apps_robot_command send_base_velocity [OPTIONS] <X> <Y> <THETA>
X
Velocity in y direction
Y
Velocity in y direction
Theta
Angular velocity
Options | Description |
---|---|
-d, --duration_secs <DURATION_SECS> | |
-h, --help | Print help information |
Usage send_joints
openrr_apps_robot_command send_joints [OPTIONS] <NAME>
Name
Client name
Option
Options | Description |
---|---|
-d, --duration | |
-h, --help | Print help information |
-i, --interpolate | Interpolate target in cartesian space. If you use this flag, joint values are not used as references but used in forward kinematics |
-j, --joint | Specify joint parameters. Like --joint 0=1.2 . In accordance with the sequence in which the "joint names" are defined in the configuration, they are numbered starting at 0 |
--max_resolution_for_interpolation <MAX_RESOLUTION_FOR_INTERPOLATION> | Max resolution for interpolation (default 0.05) |
--min_number_of_points_for_interpolation <MIN_NUMBER_OF_POINTS_FOR_INTERPOLATION> | in number of points for interpolation(default 10) |
Usage of send_joints_pose
openrr_apps_robot_command send_joints_pose [OPTIONS] <NAME> <POSE_NAME>
Name
Client name
Pose name
Pose name
Option
Options | Description |
---|---|
-d, --duration | |
-h, --help | Print help information |
Usage of send_navigation_goal
openrr_apps_robot_command send_navigation_goal [OPTIONS] <X> <Y> <YAW>
Option
Options | Description |
---|---|
-f, --frame_id <FRAME_ID> | |
-h, --help | Print help information |
-t, --timeout_secs <TIMEOUT_SECS> | Timeout second |
Usage of shell_completion
openrr_apps_robot_command shell_completion <SUBCOMMAND>
Subcommand
Subcommand | Description |
---|---|
bash | |
fish | |
help | Print this message or the help of the given subcommand(s) |
power_shell | |
zsh |
openrr_apps_robot_teleop
With openrr_apps_robot_teleop
, what used to be controlled on a GUI application can now be controlled remotely with a joystick or similar.
openrr_apps_robot_teleop
Usage
openrr_apps_robot_teleop [OPTIONS]
Options | Description |
---|---|
-c, --config-path <CONFIG_PATH> | Path to the setting file |
-h, --help | Print help information |
--log-directory <LOG_DIRECTORY> | Path to log directory for tracing FileAppender |
--robot-config <ROBOT_CONFIG> | Set options from command line. These settings take priority over the setting file specified by --config-path |
--show-default-config | Prints the default setting as TOML |
--teleop-config <TELEOP_CONFIG> | Set options from command line. These settings take priority over the setting file specified by --config-path |
Example
Button names follow gilrs layout.
Run urdf-viz
. Then connect the gamepad to your PC, load and run the configuration file for Teleop.
urdf-viz ./openrr-planner/sample.urdf &
openrr_apps_robot_teleop \
--config-path ./openrr-apps/config/sample_teleop_config_urdf_viz.toml
Pressing the assigned mode selection button (North
by default) toggles the mode, and the sub-mode selection button (East
by default) toggles the sub-mode.
PrintSpeaker: l_arm0
PrintSpeaker: r_arm0
PrintSpeaker: base
PrintSpeaker: left i k
PrintSpeaker: right i k
PrintSpeaker: pose l_arm_collision_checked zero
PrintSpeaker: l_arm0
PrintSpeaker: r_arm0
PrintSpeaker: r_arm1
PrintSpeaker: r_arm2
Example (--teleop-config)
openrr_apps_robot_teleop \
--config-path ./openrr-apps/config/sample_teleop_config_urdf_viz.toml \
--teleop-config gamepad=\"keyboard\"
This is done in the same way as example (--config) in openrr_apps_robot_command
Example (--config), which is to overwrite existing settings.
In this example, the default operation with the gamepad is switched to operation from the keyboard.
openrr_apps_joint_position_sender
The openrr_apps_joint_position_sender
allows you to specify the value of each joint for manipulators and other articulated robots.
openrr_apps_joint_position_sender
Usage
openrr_apps_joint_position_sender [OPTIONS]
Options | Description |
---|---|
-c, --config-path <CONFIG_PATH> | Path to the setting file |
--config <CONFIG> | Set options from command line. These settings take priority over the setting file specified by --config-path |
-h, --help | Print help information |
openrr_apps_velocity_sender
The openrr_apps_velocity_sender
allows you to specify a velocity to move the mobile robot.
openrr_apps_velocity_sender
Usage
openrr_apps_velocity_sender [OPTIONS]
Options | Description |
---|---|
-c, --config-path <CONFIG_PATH> | Path to the setting file |
--config <CONFIG> | Set options from command line. These settings take priority over the setting file specified by --config-path |
-h, --help | Print help information |
OpenRR Apps Configuration
Client config
Write config
By writing your own config, you can make OpenRR work with robots that are not in the sample or robots that you have created yourself. config can contain the following elements.
We recommend that VSCode users install the EvenBetterTOML
extension here.
Default config
The default is as follows. Settings are added or overwritten depending on the loaded config.
[speak_configs]
[openrr_clients_config]
self_collision_check_pairs = []
[openrr_clients_config.ik_solvers_configs]
[plugins]
robot_config
This is a list of items to be written in the Client config. Please also refer to the samples in the repository. Click here to see the sample.
Properties | Description | Type |
---|---|---|
joint_trajectory_clients | Joint trajectory clients to be used. | array string |
localization | Localization to be used. ros , urdf-viz , false , or plugin instance name. | string or boolean |
move_base | MoveBase to be used. ros , urdf-viz , false , or plugin instance name. | string or boolean |
navigation | Navigation to be used. ros , urdf-viz , false , or plugin instance name. | string or boolean |
openrr_clients_config | openrr_clients_config | |
ros_action_clients_configs | Setting ROS Action Client . | array RosControlActionClientConfig |
plugins | Setting plugin | |
ros_clients_configs | ros_clients_configs | |
ros_cmd_vel_move_base_client_config | Setting ROS MoveBase . Specify the topic you want to send by appending topic . | |
ros_localization_client_config | Setting ROS Localization . | |
ros_navigation_client_config | Setting ROS Navigation . | |
speak_configs | Setting speak . | SpeakConfig |
speakers | Speakers to be used. | string |
urdf_viz_clients_configs |
joint_trajectory_clients
Type: array string
localization
, move_base
, navigation
Type: string or boolean
Example
move_base = false
navigation = "arci_ros2"
openrr_clients_config
OpenRR Clients Config
OpenRR Clients Config | Type |
---|---|
collision_check_clients_configs | CollisionCheckClientConfig |
ik_clients_configs | IkClientConfig |
ik_solvers_configs | IkSolverConfig |
joint_trajectory_clients_container_configs | JointTrajectoryClientsContainerConfig |
joint_poses | JointsPose |
self_collision_check_pairs | array string |
urdf_full_path | string |
urdf_path | string |
Example
[openrr_clients_config]
urdf_path = "./twin_arms_robot.urdf"
self_collision_check_pairs = [
"left_shoulder:left_gripper",
"right_shoulder:right_gripper"
]
Collision Check Client Config
Collision Check Client Config | Type |
---|---|
client_name | string (required) |
name | string (required) |
self_collision_checker_config | SelfCollisionCheckerConfig |
Example
[[openrr_clients_config.collision_check_clients_configs]]
client_name = "arm_with_torso"
name = "arm_with_torso_collision_checked"
Self Collision Checker Config
Self Collision Checker Config | Type |
---|---|
prediction | double (default 0.001) |
time_interpolate_rate | double (default 0.5) |
IK Client Config
IK Client Config | Type |
---|---|
client_name | string (required) |
name | string (required) |
solver_name | string (required) |
Example
[[openrr_clients_config.ik_clients_configs]]
name = "arm_with_torso_ik"
client_name = "arm_with_torso_collision_checked"
solver_name = "arm_with_torso_ik_solver"
IK Solver Config
IK Solver Config | Type |
---|---|
allowable_angle_error_rad | double (default 0.005) |
allowable_position_error_m | double (default 0.005) |
constraints | Constraints |
ik_target | string (required) |
jacobian_multiplier | double (default 0.1) |
num_max_try | uint (default 300) |
root_node_name | string |
use_random_ik | boolean (default false) |
Example
[openrr_clients_config.ik_solvers_configs.arm_with_torso_ik_solver]
ik_target = "gripper_palm_joint"
allowable_position_error_m = 0.01
Constraints
Constraints | Type |
---|---|
ignored_joint_names | array string (default []) |
position_x | boolean (default true) |
position_y | boolean (default true) |
position_z | boolean (default true) |
rotation_x | boolean (default true) |
rotation_y | boolean (default true) |
rotation_z | boolean (default true) |
Joint Trajectory Client Container Config
Joint Trajectory Client Container Config | Type |
---|---|
clients_name | array string (required) |
name | string |
Joints Pose
Joints Pose | Type |
---|---|
client_name | string (required) |
pose_name | string (required) |
positions | array double (required) |
Example
[[openrr_clients_config.joints_poses]]
pose_name = "stand by"
client_name = "arm"
positions = [0.0, 1.2, 0.0, -0.7, 0.0, -0.2, 0.0]
ros_action_clients_configs
ROS Control Action Client Config
ROS Control Action Client Config | Type |
---|---|
complete_allowable_errors | array double (required) |
complete_timeout_sec | double (default 10.0) |
controller_name | string (required) |
joint_names | array string (required) |
joint_position_difference_limits | array double |
joint_position_limiter_strategy | JointPositionLimiterStrategy |
joint_position_limits | JointPositionLimit |
joint_velocity_limits | array double |
name | string (required) |
send_partial_joints_goal | boolean (default false) |
state_topic_name | string (required) |
wrap_with_joint_position_difference_limiter | boolean (default false) |
wrap_with_joint_position_limiter | boolean (default false) |
wrap_with_joint_velocity_limiter | boolean (default false) |
Joint Position Limiter Strategy
Joint Position Limiter Strategy | Element |
---|---|
string (enum) | "Clamp", "ClampWithWarn", "Error" |
Joint Position Limit
Joint Position Limit | Type |
---|---|
lower | double |
upper | double |
Example
[[urdf_viz_clients_configs]]
name = "foo"
joint_names = ["bar1", "bar2"]
joint_position_limits = [
{ lower = -3.0, upper = 3.0 },
{ lower = -2.0, upper = 1.5 },
]
plugins
plugin config | Type |
---|---|
instances | PluginInstance |
path |
Plugin Instance
Plugin Instance | Type | Description |
---|---|---|
args | string | Arguments passed when creating this instance. |
args_from_path | string | Pass the contents of the specified file as an argument. |
path | string (required) | Path to the plugin. If no extension is specified, the default extension for cdylib on the current OS will be selected. (linux: .so , macos: .dylib , windows: .dll ) |
type | PluginInstanceKind |
Plugin Instance Kind
Joint Position Limiter Strategy | Element |
---|---|
string (enum) | "JointTrajectoryClient", Localization", MoveBase", Navigation", "Speaker" |
ros_clients_configs
ROS Control Client Config
ROS Control Client Config | Type |
---|---|
complete_allowable_errors | array double |
complete_timeout_sec | double |
controller_name | string |
joint_names | array string |
joint_position_limits | array JointPositionLimit |
joint_velocity_limits | array double |
name | string |
send_partial_joints_goal | boolean |
state_topic_name | string |
wrap_with_joint_position_limiter | boolean (false) |
wrap_with_joint_velocity_limiter | boolean (false) |
Joint Position Limit
Joint Position Limit | Type |
---|---|
lower | double |
upper | double |
Example
[[ros_clients_configs]]
name = "arm"
joint_names = [
"shoulder_joint",
"shoulder_joint",
"upper_arm_roll_joint",
"elbow_flex_joint",
"forearm_roll_joint",
"wrist_flex_joint",
"wrist_roll_joint",
]
complete_allowable_errors = [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01]
controller_name = "arm_controller"
state_topic_name = "arm_controller/openrr/state"
ros_cmd_vel_move_base_client_config
ROS cmd_vel MoveBase Client Config
ROS cmd_vel MoveBase Config | Type |
---|---|
topic | string |
ros_localization_client_config
ROS Localization Client Config
ROS Localization Client Config | Type |
---|---|
request_final_nomotion_update_hack | boolean |
ros_navigation_client_config
ROS Navigation Client Config
ROS Navigation Client Config | Type |
---|---|
clear_costmap_before_start | boolean |
request_final_nomotion_update_hack | boolean |
speak_configs
Speak Config
Speak Config | Element |
---|---|
string(enum) | "Print" , "Audio" , "Command" or "RosEspeak" |
"RosEspeak" | Type |
---|---|
config | RosEspeakClientConfig |
"Audio" | Type |
---|---|
args | map (required) |
map | Type |
---|---|
{name} | string |
ROS Espeak Client Config
ROS Espeak Client Config | Type |
---|---|
topic | string |
Example (Audio)
[speak_configs."foo"]
type = "Audio"
[speak_configs."foo".args.map]
bar = "./bar.mp3" # Path to audio file
openrr_apps_robot_command --config-path {path to toml} speak foo bar
Example (ROSEspeak)
[speak_configs.espeak]
type = "RosEspeak"
[speak_configs.espeak.args.config]
topic = "/sample/message"
openrr_apps_robot_command --config-path {path to toml} -i
> speak espeak Hello!
data: "Hello!"
---
speakers
Type: string
urdf_viz_clients_configs
URDF-Viz Web Client Config | Type |
---|---|
joint_names | array string |
joint_position_limits | array JointPositionLimit |
joint_velocity_limits | array double |
name | string |
wrap_with_joint_position_limiter | boolean (default false) |
wrap_with_joint_velocity_limiter | boolean (default false) |
Example
[[urdf_viz_clients_configs]]
# `urdf-viz` client name
name = "arm"
# List of joints
joint_names = [
"shoulder_yaw",
"shoulder_pitch",
"shoulder_roll",
"elbow_pitch",
"wrist_yaw",
"wrist_pitch",
]
wrap_with_joint_position_limiter = true
# Range of joints
joint_position_limits = [
{ lower = -3.0, upper = 3.0 },
{ lower = -2.0, upper = 1.5 },
{ lower = -1.5, upper = 2.0 },
{ lower = -2.0, upper = 1.5 },
{ lower = -3.0, upper = 3.0 },
{ lower = -2.0, upper = 2.0 },
]
[openrr_clients_config]
# Path to URDF file
urdf_path = "./sample.urdf"
self_collision_check_pairs = [
"shoulder_yaw:gripper_linear1",
]
[[openrr_clients_config.collision_check_clients_configs]]
# Collision check client name
name = "arm_collision_checked"
# `urdf-viz` client name
client_name = "arm"
[[openrr_clients_config.ik_clients_configs]]
# IK client name
name = "arm_ik"
# Collision check client name
client_name = "arm_collision_checked"
# IK solver name
solver_name = "arm_ik_solver"
[[openrr_clients_config.joints_poses]]
# Position name
pose_name = "zero"
# Collision check client name
client_name = "arm_collision_checked"
# Position that you want to set
positions = [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
[openrr_clients_config.ik_solvers_configs.arm_ik_solver] # IK solver name (arm_ik_solver)
ik_target = "tool_fixed"
Teleop config
Write config
The previous page covered Client configurations. This page contains additional configurations for Teleop.
Items marked "required" are mandatory.
Default config
The default is as follows. Settings are added or overwritten depending on the loaded config. Since it is implemented in a HashMap, it will overwrite any already set and append for new settings.
initial_mode = ""
gamepad = "gilrs"
[control_nodes_config]
[gil_gamepad_config]
device_id = 0
[gil_gamepad_config.map]
button_map = [
["DPadLeft", "DPadLeft" ],
["Select", "Select" ],
["East", "East" ],
["DPadUp", "DPadUp" ],
["LeftTrigger", "LeftTrigger" ],
["DPadDown", "DPadDown" ],
["RightTrigger", "RightTrigger" ],
["RightTrigger2", "RightTrigger2"],
["Start", "Start" ],
["LeftTrigger2", "LeftTrigger2" ],
["Mode", "Mode" ],
["DPadRight", "DPadRight" ],
["South", "South" ],
["North", "North" ],
["RightThumb", "RightThumb" ],
["LeftThumb", "LeftThumb" ],
["West", "West" ]
]
axis_map = [
["LeftStickY", "LeftStickY" ],
["LeftStickX", "LeftStickX" ],
["RightStickX", "RightStickX"],
["DPadY", "DPadY" ],
["DPadX", "DPadX" ],
["RightStickY", "RightStickY"]
]
axis_value_map = [["LeftStickX", -1.0], ["RightStickX", -1.0]]
[plugins]
robot_teleop_config
Properties | type |
---|---|
control_nodes_config | ControlNodesConfig (required) |
gamepad | GamepadKind(string) (default "gilrs") |
gil_gamepad_config | GilGamepadConfig |
initial_mode | string |
plugins | TeleopPluginConfig |
robot_config_full_path | string |
robot_config_path | string |
control_nodes_config
Control Nodes Config
Control Nodes Config | |
---|---|
ik_node_teleop_configs | array IkNodeTeleopConfig (required) |
joints_pose_sender_config | JointsPoseSenderConfig (required) |
joy_joint_teleop_configs | array JoyJointTeleopConfig |
move_base_mode | string |
command_configs | RobotCommandConfig |
IK Node Teleop Config
IK Node Teleop Config | |
---|---|
config | IkNodeConfig (required) |
joint_trajectory_client_name | string (required) |
solver_name | string (required) |
Joint Pose Sender Config
Joint Pose Sender Config | |
---|---|
duration_secs | double (default 2.0) |
mode | string (default "pose") |
Joy Joint Teleop Config
Joy Joint Teleop Config | |
---|---|
client_name | string |
config | JoyJointTeleopNodeConfig |
IK Node Config
IK Node Config | |
---|---|
mode | string (required) |
move_step_angular | array double (default [0.05, 0.05, 0.17]) |
move_step_linear | array double (default [0.01, 0.01, 0.01]) |
step_duration_secs | double (default 0.1) |
Joy Joint Teleop Node Config
Joy Joint Teleop Node Config | |
---|---|
joint_step | double (default 0.02) |
mode | string (required) |
step_duration_secs | double (default 0.1) |
Robot Command Config
Robot Command Config | |
---|---|
file_path | string (required) |
name | string (required) |
Example
[[control_nodes_config.command_configs]]
name = "audio bar"
file_path = "sample_audio_command.txt"
[[control_nodes_config.command_configs]]
name = "ros speak"
file_path = "sample_speak_command.txt"
openrr_apps_robot_command speak foo bar
openrr_apps_robot_command speak espeak "This is topic message"
PrintSpeaker: command audio sine
PrintSpeaker: command ros speak
gamepad
string or BuiltinGamepad ("gilrs" or "keyboard"). Default is "gilrs".
gil_gamepad_config
Gil Gamepad Config
Gil Gamepad Config | |
---|---|
device_id | uint (default 0) |
map | Map |
Map
Map | |
---|---|
axis_map | array GilrsAxis Axis |
axis_value_map | array Axis double |
button_map | array GilrsButton Button |
A comparison table with Gilrs
looks like this. For reference only, as it depends on the Joystick used. If you want to assign this particular button or stick, you can change the key by following the example and mapping it to the teleop_config file.
Button and stick names follow gilrs layout.
Comparison table between GilrsAxis
and Axis
GilrsAxis | Axis | |
---|---|---|
"LeftStickX" | "LeftStickX" | (default) |
"LeftStickY" | "LeftStickY" | (default) |
"LeftZ" | "LeftTrigger" | |
"RightStickX" | "RightStickX" | (default) |
"RightStickY" | "RightStickY" | (default) |
"RightZ" | "RightTrigger" | |
"DPadX" | "DPadX" | (default) |
"DPadY" | "DPadY" | (default) |
"Unknown" | "Unknown" |
Comparison table between GilrsButton
and Button
GilrsButton | Button | |
---|---|---|
"South" | "South" | (default) |
"East" | "East" | (default) |
"North" | "North" | (default) |
"West" | "West" | (default) |
"C" | ||
"Z" | ||
"LeftTrigger" | "LeftTrigger" | (default) |
"LeftTrigger2" | "LeftTrigger2" | (default) |
"RightTrigger" | "RightTrigger" | (default) |
"RightTrigger2" | "RightTrigger2" | (default) |
"Select" | "Select" | (default) |
"Start" | "Start" | (default) |
"Mode" | "Mode" | (default) |
"LeftThumb" | "LeftThumb" | (default) |
"RightThumb" | "RightThumb" | (default) |
"DPadUp" | "DPadUp" | (default) |
"DPadDown" | "DPadDown" | (default) |
"DPadLeft" | "DPadLeft" | (default) |
"DPadRight" | "DPadRight" | (default) |
"Unknown" | "Unknown" |
Example
[gil_gamepad_config.map]
axis_map = [
# GilrsAxis Axis (user axis)
['LeftStickX', 'LeftStickX' ],
['LeftStickY', 'LeftStickY' ],
['LeftZ', 'LeftTrigger' ],
['RightStickX', 'RightStickX' ],
['RightStickY', 'RightStickY' ],
['RightZ', 'RightTrigger' ],
['DPadX', 'DPadX' ],
['DPadY', 'DPadY' ],
]
axis_value_map = [
# Axis (user axis) value
['LeftStickX', -1.0 ],
['RightStickX', -1.0 ],
['LeftStickY', -1.0 ],
['RightStickY', -1.0 ],
]
button_map = [
# GilrsButton Button(user button)
['East', 'South' ],
['C', 'East' ],
['North', 'North' ],
['South', 'West' ],
['West', 'LeftTrigger' ],
['LeftTrigger', 'LeftTrigger2' ],
['Z', 'RightTrigger' ],
['RightTrigger', 'RightTrigger2' ],
['LeftTrigger2', 'Select' ],
['RightTrigger2', 'Start' ],
['Mode', 'Mode' ],
['Select', 'LeftThumb' ],
['Start', 'RightThumb' ],
['DPadUp', 'DPadUp' ],
['DPadDown', 'DPadDown' ],
['DPadLeft', 'DPadLeft' ],
['DPadRight', 'DPadRight' ],
]
initial_mode
The initial_mode
allows you to specify the initial mode.
Example
initial_mode = "base"
plugins
Teleop Plugin Config
Teleop Plugin Config | Description | |
---|---|---|
args | string | Arguments passed when creating this instance. |
args_from_path | string | Pass the contents of the specified file as an argument. |
path | string (required) | Path to the plugin. If no extension is specified, the default extension for cdylib on the current OS will be selected. (linux: .so , macos: .dylib , windows: .dll ) |
robot_config_path
The robot_config_path
specifies the relative path to the config file.
Example
robot_config_path = "sample_robot_client_config_for_urdf_viz.toml"
Environmental Variables
If you set export OPENRR_APPS_ROBOT_CONFIG_PATH=some_path_to_config.toml
, you can skip
--config-path
. If you give --config-path
explicitly, the env var is ignored.
openrr_apps_robot_command
- Run sample commands with env var
export OPENRR_APPS_ROBOT_CONFIG_PATH=$(pwd)/openrr-apps/config/sample_robot_client_config_for_urdf_viz.toml
openrr_apps_robot_command load_commands ./openrr-apps/command/sample_cmd_urdf_viz.txt
openrr_apps_joint_position_sender
- Run for sample urdf with env var
export OPENRR_APPS_ROBOT_CONFIG_PATH=$(pwd)/openrr-apps/config/sample_robot_client_config_for_urdf_viz.toml
openrr_apps_joint_position_sender
Note
Do not forget to unset OPENRR_APPS_ROBOT_CONFIG_PATH before try other settings
Overwrite configuration at startup
By using --config
flag, you can overwrite the configuration at startup.
For example, to replace the urdf path:
openrr_apps_robot_command \
--config-path ./openrr-apps/config/sample_robot_client_config_for_urdf_viz.toml \
--config 'openrr_clients_config.urdf_path="path/to/urdf"' \
load_commands ./openrr-apps/command/sample_cmd_urdf_viz.txt
In openrr_apps_robot_teleop
, there are two flags: --robot-config
to overwrite robot config and --teleop-config
to overwrite teleop config.
For example, to run openrr_apps_robot_teleop
with arci-gamepad-keyboard
:
openrr_apps_robot_teleop \
--config-path ./openrr-apps/config/sample_teleop_config_urdf_viz.toml \
--teleop-config 'gamepad="Keyboard"'
To disable joint_position_limiter:
openrr_apps_robot_teleop \
--config-path ./openrr-apps/config/sample_teleop_config_urdf_viz.toml \
--robot-config 'urdf_viz_clients_configs[0].wrap_with_joint_position_limiter=false'
To overwrite multiple configs, separate the scripts with a semicolon or a newline. For example:
# semicolon-separated
openrr_apps_robot_teleop \
--config-path ./openrr-apps/config/sample_teleop_config_urdf_viz.toml \
--robot-config 'urdf_viz_clients_configs[0].wrap_with_joint_position_limiter=false;openrr_clients_config.urdf_path="path/to/urdf"'
# newline-separated
{
echo 'urdf_viz_clients_configs[0].wrap_with_joint_position_limiter=false'
echo 'openrr_clients_config.urdf_path="path/to/urdf"'
} > overwrite.txt
openrr_apps_robot_teleop \
--config-path ./openrr-apps/config/sample_teleop_config_urdf_viz.toml \
--robot-config "$(cat ./overwrite.txt)"
Develop OpenRR
For Developer
coming soon...
- How to develop an application using OpenRR.
- How to implement the interface with the microcontroller and software.
Troubleshooting
Basically, if it doesn't work, you can look at the output or the error log, but I will note what seems to happen most often.
Featuring ROS2
cargo build --release --features ros2
cargo install --path ./openrr-apps
Please make sure that ROS2 is enabled before these commands.
GUI Troubleshooting
Please check openrr-gui README
If this does not resolve the issue
It may be a bug in OpenRR, so it would be helpful if you could open an Issue in the repository Issues.