Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Remove enablePlannerDynamicSwitch #1919

Merged
merged 8 commits into from
Apr 15, 2019
Original file line number Diff line number Diff line change
Expand Up @@ -2,5 +2,4 @@
<launch>

<node pkg="lane_planner" type="lane_select" name="lane_select" output="log"></node>

</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,6 @@ void LaneSelectNode::initForROS()

pub1_ = nh_.advertise<autoware_msgs::Lane>("base_waypoints", 1);
pub2_ = nh_.advertise<std_msgs::Int32>("closest_waypoint", 1);

pub3_ = nh_.advertise<std_msgs::Int32>("change_flag", 1);
pub4_ = nh_.advertise<std_msgs::Int32>("/current_lane_id", 1);
pub5_ = nh_.advertise<autoware_msgs::VehicleLocation>("vehicle_location", 1);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -139,8 +139,6 @@ class PlannerX

std::vector<std::string> m_LogData;

bool enablePlannerDynamicSwitch;

protected:
//ROS messages (topics)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -88,8 +88,6 @@
<param name="mapSource" value="$(arg mapSource)" />
<param name="mapFileName" value="$(arg mapFileName)" />

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

</node>

</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -71,9 +71,6 @@ PlannerX::PlannerX()
m_ObstacleTracking.m_dt = 0.12;
m_ObstacleTracking.m_bUseCenterOnly = true;

enablePlannerDynamicSwitch = false;


int iSource = 0;
nh.getParam("/dp_planner/mapSource", iSource);
if(iSource == 0)
Expand All @@ -95,12 +92,6 @@ PlannerX::PlannerX()


std::string topic_prefix;
nh.getParam("/dp_planner/enablePlannerDynamicSwitch", enablePlannerDynamicSwitch);
if(enablePlannerDynamicSwitch){
topic_prefix = "/dp";
pub_LocalTrajectoriesRviz_dynamic = nh.advertise<visualization_msgs::MarkerArray>("local_trajectories_dynamic", 1);
pub_EnableLattice = nh.advertise<std_msgs::Int32>("enableLattice", 1);
}

pub_LocalPath = nh.advertise<autoware_msgs::Lane>(topic_prefix + "/final_waypoints", 100,true);
pub_LocalBasePath = nh.advertise<autoware_msgs::Lane>(topic_prefix + "/base_waypoints", 100,true);
Expand Down Expand Up @@ -774,34 +765,6 @@ void PlannerX::PlannerMainLoop()
ROSHelpers::ConvertFromPlannerHToAutowareVisualizePathFormat(m_LocalPlanner.m_Path, m_LocalPlanner.m_RollOuts, m_LocalPlanner, all_rollOuts);
pub_LocalTrajectoriesRviz.publish(all_rollOuts);

//Publish markers that visualize only when avoiding objects
if(enablePlannerDynamicSwitch){
visualization_msgs::MarkerArray all_rollOuts_dynamic;
std_msgs::Int32 enableLattice;
if(iDirection != 0) { // if obstacle avoidance state,
all_rollOuts_dynamic = all_rollOuts;

for(auto &ro : all_rollOuts_dynamic.markers){
ro.ns = "global_lane_array_marker_dynamic";
}
pub_LocalTrajectoriesRviz_dynamic.publish(all_rollOuts_dynamic);
enableLattice.data = 1;
}else{
visualization_msgs::Marker delMarker;
#ifndef ROS_KINETIC
delMarker.action = visualization_msgs::Marker::DELETE;
#else
delMarker.action = visualization_msgs::Marker::DELETEALL;
#endif
delMarker.ns = "global_lane_array_marker_dynamic";
all_rollOuts_dynamic.markers.push_back(delMarker);
pub_LocalTrajectoriesRviz_dynamic.publish(all_rollOuts_dynamic);
enableLattice.data = 0;
}
pub_EnableLattice.publish(enableLattice); //Publish flag of object avoidance
}


if(m_CurrentBehavior.bNewPlan)
{
std::ostringstream str_out;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@
<arg name="decelerate_vel_min" default="1.3" />
<arg name="remove_points_upto" default="2.3" />
<arg name="enable_multiple_crosswalk_detection" default="true" />
<arg name="enablePlannerDynamicSwitch" default="false" />

<node pkg="waypoint_planner" type="velocity_set" name="velocity_set" output="screen">
<param name="use_crosswalk_detection" value="$(arg use_crosswalk_detection)" />
Expand All @@ -15,7 +14,6 @@
<param name="velocity_offset" value="$(arg velocity_offset)" />
<param name="decelerate_vel_min" value="$(arg decelerate_vel_min)" />
<param name="remove_points_upto" value="$(arg remove_points_upto)" />
<param name="enablePlannerDynamicSwitch" value="$(arg enablePlannerDynamicSwitch)" />
</node>

</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -529,12 +529,10 @@ int main(int argc, char** argv)

bool use_crosswalk_detection;
bool enable_multiple_crosswalk_detection;
bool enablePlannerDynamicSwitch;

std::string points_topic;
private_nh.param<bool>("use_crosswalk_detection", use_crosswalk_detection, true);
private_nh.param<bool>("enable_multiple_crosswalk_detection", enable_multiple_crosswalk_detection, true);
private_nh.param<bool>("enablePlannerDynamicSwitch", enablePlannerDynamicSwitch, false);


private_nh.param<std::string>("points_topic", points_topic, "points_lanes");
Expand Down Expand Up @@ -570,11 +568,7 @@ int main(int argc, char** argv)
ros::Publisher obstacle_waypoint_pub = nh.advertise<std_msgs::Int32>("obstacle_waypoint", 1, true);

ros::Publisher final_waypoints_pub;
if(enablePlannerDynamicSwitch){
final_waypoints_pub = nh.advertise<autoware_msgs::Lane>("astar/final_waypoints", 1, true);
}else{
final_waypoints_pub = nh.advertise<autoware_msgs::Lane>("final_waypoints", 1, true);
}
final_waypoints_pub = nh.advertise<autoware_msgs::Lane>("final_waypoints", 1, true);

ros::Rate loop_rate(LOOP_RATE);
while (ros::ok())
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,6 @@
format: Autoware Launcher Plugin Version 0.1
rosxml: $(find lane_planner)/launch/lane_select.launch
args:
- {name: enablePlannerDynamicSwitch, type: bool, default: false}
args: []
panel:
widget: node.panel
frames:
- {target: args.enablePlannerDynamicSwitch, widget: basic.bool}
frames: []
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,6 @@ args:
- {name: decelerate_vel_min, type: real, default: 1.3}
- {name: remove_points_upto, type: real, default: 2.3}
- {name: enable_multiple_crosswalk_detection, type: bool, default: true}
- {name: enablePlannerDynamicSwitch, type: bool, default: false}

panel:
widget: node.panel
Expand All @@ -18,4 +17,3 @@ panel:
- {target: args.decelerate_vel_min, widget: basic.real}
- {target: args.remove_points_upto, widget: basic.real}
- {target: args.enable_multiple_crosswalk_detection, widget: basic.bool}
- {target: args.enablePlannerDynamicSwitch, widget: basic.bool}
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
children: []
config:
args.enablePlannerDynamicSwitch: false
config: {}
plugin: refs/lane_select
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
children: []
config:
args.decelerate_vel_min: 1.3
args.enablePlannerDynamicSwitch: false
args.enable_multiple_crosswalk_detection: true
args.points_topic: points_no_ground
args.remove_points_upto: 2.3
Expand Down