Automated Parking Valet with ROS 2 in MATLAB
This example shows how you can distribute Automated Parking Valet (Automated Driving Toolbox) application among various nodes in a ROS 2 network.
Overview
This example is an extension of the Automated Parking Valet (Automated Driving Toolbox) example in Automated Driving Toolbox™. A typical autonmous application has the following components.
For simplicity, this example concentrates on Planning, Control, and a simplified Vehicle Model. The example uses prerecorded data to substitute localization information.
This application demonstrates a typical split of various functions into ROS nodes. The following picture shows how the above example is split into various nodes. Each node: Planning, Control and Vehicle is a ROS node implementing the functionalities shown as below. The interconnections between the nodes show the topics used on each interconnection of the nodes.
Setup
First, load a route plan and a given costmap used by the behavior planner and path analyzer. Behavior Planner, Path Planner, Path Analyzer, Lateral and Lognitudinal Controllers are implemented by helper classes, which are setup with this example helper function call.
exampleHelperROSValetSetupGlobals; % The initialized globals are organized as fields in the global structure % |valet|. disp(valet)
mapLayers: [1×1 struct] costmap: [1×1 vehicleCostmap] vehicleDims: [1×1 vehicleDimensions] maxSteeringAngle: 35 data: [1×1 struct] routePlan: [4×3 table] currentPose: [4 12 0] vehicleSim: [1×1 ExampleHelperROSValetVehicleSimulator] behavioralPlanner: [1×1 ExampleHelperROSValetBehavioralPlanner] motionPlanner: [1×1 pathPlannerRRT] goalPose: [56 11 0] refPath: [1×1 driving.Path] transitionPoses: [13×3 double] directions: [528×1 double] currentVel: 0 approxSeparation: 0.1000 numSmoothPoses: 528 maxSpeed: 5 startSpeed: 0 endSpeed: 0 refPoses: [528×3 double] cumLengths: [528×1 double] curvatures: [528×1 double] refVelocities: [528×1 double] sampleTime: 0.1000 lonController: [1×1 ExampleHelperROSValetLongitudinalController] controlRate: [1×1 ExampleHelperROSValetFixedRate] pathAnalyzer: [1×1 ExampleHelperROSValetPathAnalyzer] parkPose: [36 44 90]
Use nodes to split the functions in the application. This example uses three nodes: planningNode
, controlNode
, and vehicleNode
.
Planning
The Planning node calculates each path segment based on the current vehicle position. This node is responsible for generating the smooth path and publishes the path to the network.
This node publishes these topics:
/smoothpath
/velprofile
/directions
/speed
/nextgoal
The node subscribes to these topics:
/currentvel
/currentpose
/desiredvel
/reachgoal
On receiving a /reachgoal
message, the node runs the exampleHelperROS2ValetPlannerCallback
callback, which plans the next segment.
% Create planning node. planningNode = ros2node('planning'); % Create publishers for planning node. Specify the message types the first % time you create a publisher or subscriber for a topic. planning.PathPub = ros2publisher(planningNode, '/smoothpath', 'std_msgs/Float64MultiArray'); planning.VelPub = ros2publisher(planningNode, '/velprofile', 'std_msgs/Float64MultiArray'); planning.DirPub = ros2publisher(planningNode, '/directions', 'std_msgs/Float64MultiArray'); planning.SpeedPub = ros2publisher(planningNode,'/speed','std_msgs/Float64MultiArray'); planning.NxtPub = ros2publisher(planningNode, '/nextgoal', 'geometry_msgs/Pose2D'); % Create subscribers for planning node. planning.CurVelSub = ros2subscriber(planningNode, '/currentvel', 'std_msgs/Float64'); planning.CurPoseSub = ros2subscriber(planningNode, '/currentpose', 'geometry_msgs/Pose2D'); planning.DesrVelSub = ros2subscriber(planningNode, '/desiredvel', 'std_msgs/Float64'); % Create GoalReachSub part of planning node and provide the callback. GoalReachSub = ros2subscriber(planningNode, '/reachgoal', 'std_msgs/Bool'); GoalReachSub.NewMessageFcn = @(msg)exampleHelperROS2ValetPlannerCallback(msg, planning, valet);
Control
The Control node is responsible for longitudinal and lateral controllers. This node publishes these topics:
/steeringangle
/accelcmd
/decelcmd
/vehdir
/reachgoal
The node subscribes to these topics:
/smoothpath
/directions
/speed
/currentpose
/currentvel
/nextgoal
/velprofile
On receiving a /velprofile
message, the node runs the exampleHelperROS2ValetControlCallback
callback, which sends control messages to the vehicle
% Create control node controlNode = ros2node('control'); % Create publishers for control node control.SteeringPub = ros2publisher(controlNode, '/steeringangle', 'std_msgs/Float64'); control.AccelPub = ros2publisher(controlNode, '/accelcmd', 'std_msgs/Float64'); control.DecelPub = ros2publisher(controlNode, '/decelcmd', 'std_msgs/Float64'); control.VehDirPub = ros2publisher(controlNode, '/vehdir', 'std_msgs/Float64'); control.VehGoalReachPub = ros2publisher(controlNode, '/reachgoal'); % Create subscribers for control node. Since all the message types for the % topics are determined above, we can use the shorter version to create % subscribers control.PathSub = ros2subscriber(controlNode, '/smoothpath'); control.DirSub = ros2subscriber(controlNode, '/directions'); control.SpeedSub = ros2subscriber(controlNode, '/speed'); control.CurPoseSub = ros2subscriber(controlNode, '/currentpose'); control.CurVelSub = ros2subscriber(controlNode, '/currentvel'); control.NextGoalSub = ros2subscriber(controlNode, '/nextgoal'); % Create VelProfSub for control node and provide the callback VelProfSub = ros2subscriber(controlNode, '/velprofile'); VelProfSub.NewMessageFcn = @(msg)exampleHelperROS2ValetControlCallback(msg, control, valet);
Vehicle
The Vehicle node is responsible for simulating the vehicle model. This node publishes these topics:
/currentvel
/currentpose
The node subscribes to these topics:
/accelcmd
/decelcmd
/vehdir
/steeringangle
% On receiving a |/steeringangle| message, the vehicle simulator is run in % the |exampleHelperROS2ValetVehicleCallback| callback. % % <<../exampleHelperROSValetVehicleNode.PNG>> % % Create vehicle node. vehicleNode = ros2node('vehicle'); % Create publishers for vehicle node. vehicle.CurVelPub = ros2publisher(vehicleNode, '/currentvel'); vehicle.CurPosePub = ros2publisher(vehicleNode, '/currentpose'); % Create subscribers for vehicle node. vehicle.AccelSub = ros2subscriber(vehicleNode, '/accelcmd'); vehicle.DecelSub = ros2subscriber(vehicleNode, '/decelcmd'); vehicle.DirSub = ros2subscriber(vehicleNode, '/vehdir'); % Create SteeringSub which runs the vehicle simulator as part of callback. SteeringSub = ros2subscriber(vehicleNode, '/steeringangle', ... @(msg)exampleHelperROS2ValetVehicleCallback(msg, vehicle, valet));
Initialize Simulation
To initialize the simulation, send the first velocity message and current pose message. This message causes the planner to start the planning loop.
curVelMsg = ros2message(vehicle.CurVelPub); curVelMsg.data = valet.vehicleSim.getVehicleVelocity; send(vehicle.CurVelPub, curVelMsg); curPoseMsg = ros2message(vehicle.CurPosePub); curPoseMsg.x = valet.currentPose(1); curPoseMsg.y = valet.currentPose(2); curPoseMsg.theta = valet.currentPose(3); send(vehicle.CurPosePub, curPoseMsg); reachMsg = ros2message(control.VehGoalReachPub); reachMsg.data = true; send(control.VehGoalReachPub, reachMsg);
Main Loop
The main loop waits for the behavioralPlanner
to say the vehicle reached the prepark position.
while ~reachedDestination(valet.behavioralPlanner) pause(1); end % Show vehicle simulation figure showFigure(valet.vehicleSim);
Park Maneuver
The parking maneuver callbacks are slightly different from the normal driving manueuver. Replace the callbacks for the /velprofile
and /reachgoal
subscribers.
VelProfSub.NewMessageFcn = @(msg)exampleHelperROS2ValetParkControlCallback(msg, control, valet); GoalReachSub.NewMessageFcn = @(msg)exampleHelperROS2ValetParkManeuver(msg, planning, valet); reachMsg = ros2message(control.VehGoalReachPub); reachMsg.data = false; send(control.VehGoalReachPub, reachMsg); % Receive a message from the |/velprofile| topic using the subcriber. This % waits until a new message is received. Since subscriber callback for % |/reachgoal| topic sends the message to this topic, waiting for the new % message ensures the correct execution order of the callbacks. receive(VelProfSub, 4); % Receive a message from the |/reachgoal| topic using the subcriber. This % waits until a new message is received. Display the figure. The vehicle % has completed the full automated valet manuever. receive(GoalReachSub); exampleHelperROSValetCloseFigures; snapnow;
Delete the simulator and shutdown all the nodes by clearing publishers, subscribers and node handles.
delete(valet.vehicleSim); % Clear variables that were created above. clear('valet'); GoalReachSub.NewMessageFcn = []; VelProfSub.NewMessageFcn = []; clear('planning', 'planningNode', 'GoalReachSub'); clear('control', 'controlNode', 'VelProfSub'); clear('vehicle', 'vehicleNode', 'SteeringSub'); clear('curPoseMsg', 'curVelMsg', 'reachMsg');