hatem-darweesh / core_planning

Apache License 2.0
10 stars 13 forks source link

openplanner v1.15 #13

Closed ahuazuipiaoliang closed 2 years ago

ahuazuipiaoliang commented 3 years ago

I’ve been testing the Openplanner 1.15 branch of Autoware using lanelet2 map. I was using imm ukf tracker for object detection and tracking. The local planner was able to generate the local trajectories with cost, and was able to select different rollouts. But it can not slow down when it detected obstacles(all rollouts turned to be red). I was wondering that if there was some parameters set wrong?

there are my launch files below.

  1. op_common_params.launch

    
    <!-- -->
    <launch>
    
    <arg name="mapSource"                   default="3" /> <!-- Autoware=0, Vector Map Folder=1, kml=2, lanelet2 file=3, kml map file path from runtime manager = 4 -->
    <arg name="mapFileName"                 default="/home/team1/Desktop/factory_20210913.osm" />
    <arg name="lanelet2_origin"             default="0,0,0," /> <!-- GPS origin for lanelet2 map files, Lat, Long, Alt  -->
    
    <arg name="pathDensity"                 default="0.3" />
    <arg name="rollOutDensity"              default="0.5" />
    <arg name="rollOutsNumber"              default="8" />
    
    <arg name="maxLocalPlanDistance"        default="50" /> 
    <arg name="horizonDistance"             default="200" />
    
    <arg name="minFollowingDistance"        default="20.0" /> <!-- should be bigger than Distance to follow --> 
    <arg name="minDistanceToAvoid"          default="15.0" /> <!-- should be smaller than minFollowingDistance and larger than maxDistanceToAvoid -->
    <arg name="maxDistanceToAvoid"          default="10.0" /> <!-- should be smaller than minDistanceToAvoid -->
    <arg name="speedProfileFactor"          default="1.0" /> <!-- how fast the vehicle should drive through the corners and curves, less than (1) means slower speeds in the curves, larger than (1) means faster in the curves -->   
    <arg name="curveSlowDownRatio"          default="1.0" /> <!-- how early or late to brake for upcoming turn. 1 is automatically as openplanner calculates it, Smaller than 1 means late braking, greater than 1 means brake early, this value is a ratio -->
    
    <arg name="smoothingDataWeight"         default="0.2" />
    <arg name="smoothingSmoothWeight"       default="0.2" />    
    
    <arg name="horizontalSafetyDistance"    default="0.4" />
    <arg name="verticalSafetyDistance"      default="1.5" />
    
    <arg name="enableSwerving"              default="true" />
    <arg name="enableFollowing"             default="false" />  
    <arg name="enableTrafficLightBehavior"  default="false" />
    <arg name="enableStopSignBehavior"      default="false" />  
    <arg name="enableLaneChange"            default="false" />  
    
    <!-- Vehicle Info, shared with controller and simulation -->
    <arg name="height"                      default="1.5"  />
    <arg name="front_length"                default="1.25"  />
    <arg name="back_length"                 default="1.25"  />
    <arg name="width"                       default="1.5"  />
    <arg name="length"                      default="2.5"  />   
    <arg name="wheelBaseLength"             default="2.2"  />
    <arg name="turningRadius"               default="3.0"  />
    <arg name="maxWheelAngle"               default="0.63" /> <!-- radians -->
    <arg name="steeringDelay"               default="0.6" /> <!-- time steering wheel take to turn from zero to max left or right -->
    <arg name="minPursuiteDistance"         default="5.0" /> <!-- min distance to forward following target point on the trajectory  -->
    <arg name="maxAcceleration"             default="3.0" /> <!-- m/s*s -->
    <arg name="maxDeceleration"             default="-10.0" /> <!-- m/s*s -->
    <arg name="maxVelocity"                 default="3.0" /> <!-- m/s -->
    <arg name="minVelocity"                 default="0.1" /> <!-- m/s -->
    <!-- ................................................... -->
    
    <!-- Internal ACC parameters, only used inside the LocalPlanner (Behavior Selector node) -->
    <arg name="use_internal_acc"            default="false" /> <!-- If enabled, the velocity associated with the final trajectory is the final speed profile needed to be followed by the controller, including following and stopping --> 
    <arg name="accelerationPushRatio"       default="1.0" /> <!-- push the velocity to increase even when the velocity feedback signal from sensing is very small or delayed, contribute to final acceleration. where 1 predefined acceleration value is used --> 
    <arg name="brakingPushRatio"            default="1.0" /> <!-- push the velocity to decrease even when the velocity feedback signal from sensing is very small or delayed, contribute to final deceleration. where 1 predefined deceleration value is used-->    
    <!-- ................................................... -->
    
    <arg name="additionalBrakingDistance"   default="2.0" />
    <arg name="goalDiscoveryDistance"       default="1.0" />
    
    <arg name="giveUpDistance"              default="1.0" />
    
    <arg name="velocitySource"              default="1" /> <!-- read velocities from (0- Odometry, 1- autoware current_velocities, 2- car_info, 3- vehicle status ) "" -->
    <arg name="vel_odom_topic"              default="/odometry" />
    <arg name="vel_curr_topic"              default="/current_velocity" />
    <arg name="vel_can_topic"               default="/can_info" />
    <arg name="vehicle_status_topic"        default="/vehicle_status" />
    
    <arg name="experimentName"              default="" />       
    
    <arg name="objects_input_topic"         default="/tracking/objects" />
    
    <node pkg="op_local_planner" type="op_common_params" name="op_common_params" output="screen">   
        <param name="mapSource"                 value="$(arg mapSource)" /> <!-- Autoware=0, Vector Map Folder=1, kml=2 -->
        <param name="mapFileName"               value="$(arg mapFileName)" />
        <param name="lanelet2_origin"           value="$(arg lanelet2_origin)" />
    
        <param name="pathDensity"               value="$(arg pathDensity)" />
        <param name="rollOutDensity"            value="$(arg rollOutDensity)" />
        <param name="rollOutsNumber"            value="$(arg rollOutsNumber)"    />
    
        <param name="maxLocalPlanDistance"      value="$(arg maxLocalPlanDistance)" />  
        <param name="horizonDistance"           value="$(arg horizonDistance)" />   
        <param name="minFollowingDistance"      value="$(arg minFollowingDistance)"  />     
        <param name="minDistanceToAvoid"        value="$(arg minDistanceToAvoid)" /> 
        <param name="maxDistanceToAvoid"        value="$(arg maxDistanceToAvoid)"  /> 
        <param name="speedProfileFactor"        value="$(arg speedProfileFactor)"  />   
        <param name="smoothingDataWeight"       value="$(arg smoothingDataWeight)"  />
        <param name="smoothingSmoothWeight"     value="$(arg smoothingSmoothWeight)"  />    
        <param name="horizontalSafetyDistance"  value="$(arg horizontalSafetyDistance)"  />
        <param name="verticalSafetyDistance"    value="$(arg verticalSafetyDistance)"  />   
        <param name="enableSwerving"            value="$(arg enableSwerving)"  />
        <param name="enableFollowing"           value="$(arg enableFollowing)" />   
        <param name="enableTrafficLightBehavior" value="$(arg enableTrafficLightBehavior)" />
        <param name="enableStopSignBehavior"    value="$(arg enableStopSignBehavior)" />    
        <param name="enableLaneChange"          value="$(arg enableLaneChange)" />
    
        <param name="height"                    value="$(arg height)"  />       
        <param name="front_length"              value="$(arg front_length)"  />
        <param name="back_length"               value="$(arg back_length)"  />
        <param name="width"                     value="$(arg width)"  />
        <param name="length"                    value="$(arg length)"  />       
        <param name="wheelBaseLength"           value="$(arg wheelBaseLength)"  />
        <param name="turningRadius"             value="$(arg turningRadius)"  />
        <param name="maxWheelAngle"             value="$(arg maxWheelAngle)" />
        <param name="steeringDelay"             value="$(arg steeringDelay)" />
        <param name="minPursuiteDistance"       value="$(arg minPursuiteDistance)"  />
        <param name="maxAcceleration"           value="$(arg maxAcceleration)" />
        <param name="maxDeceleration"           value="$(arg maxDeceleration)" />
        <param name="maxVelocity"               value="$(arg maxVelocity)" />
        <param name="minVelocity"               value="$(arg minVelocity)" />
        <param name="use_internal_acc"          value="$(arg use_internal_acc)" />
        <param name="accelerationPushRatio"     value="$(arg accelerationPushRatio)" />
        <param name="brakingPushRatio"          value="$(arg brakingPushRatio)" />
        <param name="curveSlowDownRatio"        value="$(arg curveSlowDownRatio)" />
    
        <param name="additionalBrakingDistance" value="$(arg additionalBrakingDistance)"  />
        <param name="goalDiscoveryDistance"     value="$(arg goalDiscoveryDistance)"  />
        <param name="giveUpDistance"            value="$(arg giveUpDistance)"  />
        <param name="velocitySource"            value="$(arg velocitySource)" /> 
        <param name="vel_odom_topic"            value="$(arg vel_odom_topic)" />
        <param name="vel_curr_topic"            value="$(arg vel_curr_topic)" />
        <param name="vel_can_topic"             value="$(arg vel_can_topic)" />         
        <param name="vehicle_status_topic"      value="$(arg vehicle_status_topic)" />
        <param name="experimentName"            value="$(arg experimentName)" />    
        <param name="objects_input_topic"       value="$(arg objects_input_topic)" />   
    </node>             


2.op_behavior_selector.launch
```xml
<launch>
    <!-- Behavior selector specific parameters -->

    <arg name="evidence_trust_number"   default="3"/>
    <arg name="use_sim_time"            default="false"/>
    <arg name="show_driving_path"       default="true"/>    

    <node pkg="op_local_planner" type="op_behavior_selector" name="op_behavior_selector" output="screen">

    <param name="evidence_trust_number"     value="$(arg evidence_trust_number)"/>              
    <param name="use_sim_time"              value="$(arg use_sim_time)" />
    <param name="show_driving_path"         value="$(arg show_driving_path)" />

    </node>             

</launch>

3.op_motion_predictor.launch

<launch>    

    <arg name="max_distance_to_lane"    default="1.0"/>
    <arg name="min_prediction_distance" default="0.5"/> <!-- in meters -->
    <arg name="min_prediction_time"     default="1.5"/> <!-- in seconds -->
    <arg name="enableGenrateBranches"   default="true"/>
    <arg name="enableCurbObstacles"     default="true" />
    <arg name="distanceBetweenCurbs"    default="2.0" />
    <arg name="visualizationTime"       default="0.01" />
    <arg name="enableStepByStepSignal"  default="false" />
    <arg name="enableParticleFilterPrediction"  default="false" />

    <!-- all weights sum must equal 1 -->
    <!-- ............................ -->
    <arg name="pose_weight_factor"  default="0.2" />
    <arg name="dir_weight_factor"   default="0.2" />
    <arg name="vel_weight_factor"   default="0.2" />
    <arg name="acc_weight_factor"   default="0.2" />
    <arg name="ind_weight_factor"   default="0.2" />
    <!-- ............................ -->

    <arg name="particles_number"    default="50" /> 
    <arg name="min_particles_num"   default="2" />
    <arg name="keep_percentage"     default="0.5" />

    <node pkg="op_local_planner" type="op_motion_predictor" name="op_motion_predictor" output="screen">     

        <param name="max_distance_to_lane"      value="$(arg max_distance_to_lane)"/>
        <param name="min_prediction_distance"   value="$(arg min_prediction_distance)"/>
        <param name="min_prediction_time"       value="$(arg min_prediction_time)"/>
        <param name="enableGenrateBranches"     value="$(arg enableGenrateBranches)"/>
        <param name="enableCurbObstacles"       value="$(arg enableCurbObstacles)" />
        <param name="distanceBetweenCurbs"      value="$(arg distanceBetweenCurbs)" />
        <param name="visualizationTime"         value="$(arg visualizationTime)" />
        <param name="enableStepByStepSignal"    value="$(arg enableStepByStepSignal)" />
        <param name="enableParticleFilterPrediction"    value="$(arg enableParticleFilterPrediction)" />

        <param name="pose_weight_factor"    value="$(arg pose_weight_factor)" />
        <param name="dir_weight_factor"     value="$(arg dir_weight_factor)" />
        <param name="vel_weight_factor"     value="$(arg vel_weight_factor)" />
        <param name="acc_weight_factor"     value="$(arg acc_weight_factor)" />
        <param name="ind_weight_factor"     value="$(arg ind_weight_factor)" />

        <param name="particles_number"      value="$(arg particles_number)" />
        <param name="min_particles_num"     value="$(arg min_particles_num)" />
        <param name="keep_percentage"       value="$(arg keep_percentage)" />

    </node>

</launch>

4.op_trajectory_evaluator.launch

<launch>
    <!-- Trajectory Evaluation Specific Parameters -->

    <arg name="enablePrediction" default="true" />                          
    <arg name="keepCurrentTrajectory" default="true" />

    <!-- all weights sum must equal 1 -->
    <!-- ............................ -->
    <arg name="weight_priority"     default="0.2"/>
    <arg name="weight_transition"   default="0.2"/>
    <arg name="weight_longitudinal" default="0.2"/>
    <arg name="weight_lateral"      default="0.2"/>
    <arg name="weight_lane_change"  default="0.2"/>
    <!-- ............................ -->

    <arg name="collision_time"  default="6"/> <!-- in seconds -->

    <node pkg="op_local_planner" type="op_trajectory_evaluator" name="op_trajectory_evaluator" output="screen">

        <param name="enablePrediction" value="$(arg enablePrediction)" />                                           
        <param name="keepCurrentTrajectory" value="$(arg keepCurrentTrajectory)" />

        <param name="weight_priority" value="$(arg weight_priority)" />
        <param name="weight_transition" value="$(arg weight_transition)" />
        <param name="weight_longitudinal" value="$(arg weight_longitudinal)" />
        <param name="weight_lateral" value="$(arg weight_lateral)" />
        <param name="weight_lane_change" value="$(arg weight_lane_change)" />       
        <param name="collision_time" value="$(arg collision_time)" />

    </node>                 
</launch>

5.op_trajectory_generator.launch

<launch>
    <!-- Trajectory Generation Specific Parameters -->
    <arg name="samplingTipMargin"       default="4"  /> 
    <arg name="samplingOutMargin"       default="12" /> 
    <arg name="samplingSpeedFactor"     default="1.0" />        
    <arg name="enableHeadingSmoothing"  default="false" />
    <arg name="startFromFrontAxel"      default="false" />
    <arg name="enableForwardSimulation" default="false" />

    <node pkg="op_local_planner" type="op_trajectory_generator" name="op_trajectory_generator" output="screen">

    <param name="samplingTipMargin"         value="$(arg samplingTipMargin)"  /> 
    <param name="samplingOutMargin"         value="$(arg samplingOutMargin)" /> 
    <param name="samplingSpeedFactor"       value="$(arg samplingSpeedFactor)" />       
    <param name="enableHeadingSmoothing"    value="$(arg enableHeadingSmoothing)" />
    <param name="startFromFrontAxel"        value="$(arg startFromFrontAxel)" />
    <param name="enableForwardSimulation"   value="$(arg enableForwardSimulation)" />

    </node>             

</launch>
hatem-darweesh commented 3 years ago

You need to enable the following option to activate the object detection for OpenPlanner change "false" in:

to "true"