Generation of ROS2 packages
The functionality presented here was introduced in opengen version 0.11.0a1.
What is ROS2
ROS2 is the successor of the Robot Operating System (ROS). It provides tools, libraries, and communication mechanisms that make it easier to build distributed robotic applications.
In ROS2, functionality is organised in nodes which exchange data by publishing and subscribing to topics using typed messages. This makes ROS2 a natural fit for connecting optimizers, controllers, estimators, and sensors in robotics systems.
ROS2 + OpEn
OpEn can generate ready-to-use ROS2 packages directly from a parametric optimizer. The generated package exposes the optimizer as a ROS2 node, includes the required message definitions, and provides the files needed to build, configure, and launch it inside a ROS2 workspace.
The input and output messages are the same as in the ROS1 package documentation.
Configuration Parameters
The configuration parameters are the same as in the ROS1 package documentation: you can configure the node rate, the input topic name, and the output topic name.
In ROS2, these settings are stored using the ROS2 parameter-file format in config/open_params.yaml:
/**:
ros__parameters:
result_topic: "result"
params_topic: "parameters"
rate: 10.0
Code generation
To generate a ROS2 package from Python, create a RosConfiguration object and attach it to the build configuration using .with_ros2(...).
Example
import opengen as og
import casadi.casadi as cs
u = cs.SX.sym("u", 5)
p = cs.SX.sym("p", 2)
phi = og.functions.rosenbrock(u, p)
problem = og.builder.Problem(u, p, phi) \
.with_constraints(og.constraints.Ball2(None, 1.5))
meta = og.config.OptimizerMeta() \
.with_optimizer_name("rosenbrock_ros2")
ros2_config = og.config.RosConfiguration() \
.with_package_name("parametric_optimizer_ros2") \
.with_node_name("open_node_ros2") \
.with_rate(10)
build_config = og.config.BuildConfiguration() \
.with_build_directory("my_optimizers") \
.with_ros2(ros2_config)
builder = og.builder.OpEnOptimizerBuilder(problem, meta, build_config)
builder.build()
Note the use of with_ros2 and note that RosConfiguration is the same config
class as in ROS1.
This generates the optimizer in my_optimizers/rosenbrock_ros2, and the ROS2
package is created inside that directory as parametric_optimizer_ros2.
You can inspect the auto-generated ROS2 package here.
Use the auto-generated ROS2 package
OpEn generates a README.md file inside the generated ROS2 package with detailed instructions. In brief, the workflow is:
- Build the package with
colcon build - Source the generated workspace setup script
- Run the node with
ros2 run - Publish optimization requests on the input topic and read results from the output topic
For example, from inside the generated package directory:
- bash
- zsh
colcon build --packages-select parametric_optimizer_ros2
source install/setup.bash
ros2 run parametric_optimizer_ros2 open_node_ros2
colcon build --packages-select parametric_optimizer_ros2
source install/setup.zsh
ros2 run parametric_optimizer_ros2 open_node_ros2
In a second terminal:
- bash
- zsh
source install/setup.bash
ros2 topic pub --once /parameters parametric_optimizer_ros2/msg/OptimizationParameters \
"{parameter: [1.0, 2.0], initial_guess: [0.0, 0.0, 0.0, 0.0, 0.0], initial_y: [], initial_penalty: 15.0}"
ros2 topic echo /result --once
source install/setup.zsh
ros2 topic pub --once /parameters parametric_optimizer_ros2/msg/OptimizationParameters \
"{parameter: [1.0, 2.0], initial_guess: [0.0, 0.0, 0.0, 0.0, 0.0], initial_y: [], initial_penalty: 15.0}"
ros2 topic echo /result --once
If ROS2 cannot write to its default log directory, set an explicit writable log path before running the node:
mkdir -p .ros_log
export ROS_LOG_DIR="$PWD/.ros_log"
On some systems, the generated node may start but not appear in the ROS2 graph. If ros2 topic pub keeps printing Waiting for at least 1 matching subscription(s)..., set
RMW_IMPLEMENTATION=rmw_fastrtps_cpp in both terminals before sourcing the generated workspace and running any ros2 commands:
export RMW_IMPLEMENTATION=rmw_fastrtps_cpp
This should only be needed if ROS2 discovery is not working correctly with your default middleware.
To verify that the node is visible, you can run:
ros2 node list --no-daemon --spin-time 5
ros2 topic list --no-daemon --spin-time 5
The first command should list the running node, for example /open_node_ros2. The second should list the available topics, including /parameters and /result.
To read a single optimizer response, you can use:
ros2 topic echo /result --once
This subscribes to the result topic, prints one OptimizationResult message, and then exits.
The above command will return a message that looks as follows
solution:
- 0.5352476095477849
- 0.8028586510585609
- 0.6747818561706652
- 0.7747513439588263
- 0.5131839675113338
inner_iterations: 41
outer_iterations: 6
status: 0
cost: 1.1656771801253916
norm_fpr: 2.1973496274068953e-05
penalty: 150000.0
lagrange_multipliers: []
infeasibility_f1: 0.0
infeasibility_f2: 3.3074097972366455e-05
solve_time_ms: 0.2175
See the specification of OptimizationResult
# Constants match the enumeration of status codes
uint8 STATUS_CONVERGED=0
uint8 STATUS_NOT_CONVERGED_ITERATIONS=1
uint8 STATUS_NOT_CONVERGED_OUT_OF_TIME=2
uint8 STATUS_NOT_CONVERGED_COST=3
uint8 STATUS_NOT_CONVERGED_FINITE_COMPUTATION=4
float64[] solution # solution
uint8 inner_iterations # number of inner iterations
uint16 outer_iterations # number of outer iterations
uint8 status # status code
float64 cost # cost value at solution
float64 norm_fpr # norm of FPR of last inner problem
float64 penalty # penalty value
float64[] lagrange_multipliers # vector of Lagrange multipliers
float64 infeasibility_f1 # infeasibility wrt F1
float64 infeasibility_f2 # infeasibility wrt F2
float64 solve_time_ms # solution time in ms
Instead of starting the node with ros2 run, you can also use the generated launch file:
ros2 launch parametric_optimizer_ros2 open_optimizer.launch.py
The launch file starts the auto-generated node and loads its parameters from config/open_params.yaml, where you can adjust settings such as the input topic, output topic, and node rate.
Inside the ROS2 package
The auto-generated ROS2 package contains everything needed to build and run the optimizer as a ROS2 node.
msg/contains the auto-generated message definitions, includingOptimizationParameters.msgandOptimizationResult.msgsrc/contains the C++ node implementation that wraps the optimizerinclude/contains the corresponding C++ headersconfig/open_params.yamlstores runtime parameters such as the input topic, output topic, and node ratelaunch/open_optimizer.launch.pyprovides a ready-to-use ROS2 launch fileCMakeLists.txtandpackage.xmldefine the ROS2 package and its build dependenciesREADME.mdcontains package-specific build and usage instructions