SMACC states can be configured from the ros parameter server based on their hierarchy and their class name. It is responsibility of the user not to have two different state names at the same level (even if the namespace is distinct since the namespace is trimmed for parameters)
For example, imagine a StateMachine that begins by moving the mobile robot to some initial position, and then moving it to some other position relative to the initial position. You could put the navigation parameters in a ros configuration yaml file like this (and avoid hardcoding):
MyStateMachine: State1: #Go to some initial position NavigationOrthogonal: Navigate: start_position_x: 3 start_position_y: 0 State2: #Go to some initial position NavigationOrthogonal: Navigate: initial_orientation_index: 0 # the initial index of the linear motion (factor of angle_increment_degrees) angle_increment_degree: 90 # the increment of angle between to linear motions linear_trajectories_count: 2 # the number of linear trajectories of the radial
Then, the c++ code for the State MyStateMachine/State1/NavigationOrthogonal/Navigate could contain the following parameter reading funcionality:
struct Navigate : SmaccState<Navigate, NavigationOrthogonalLine> { public: using SmaccState::SmaccState; void onEntry() { geometry_msgs::Point p; param("start_position_x", p.x, 0); param("start_position_y", p.y, 0); } }
The param template method reads from the parameters server delegating to the method defined ros::NodeHandle handle does but already located at the exact point in the parameter name hierarchy associated to this state. SMACC is also able have methods getParam and setParam that are delegated to ros::NodeHandle in the same way.