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

Cleanup WaypointState.msg and add steering_state=STR_BACK #1822

Merged
merged 1 commit into from
Jan 11, 2019
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -284,8 +284,8 @@ void DecisionMakerNode::setWaypointState(autoware_msgs::LaneArray& lane_array)
lane.waypoints.at(wp_idx).pose.pose.position.y, lane.waypoints.at(wp_idx + 1).pose.pose.position.x,
lane.waypoints.at(wp_idx + 1).pose.pose.position.y))
{
lane.waypoints.at(wp_idx).wpstate.stopline_state = g_vmap.findByKey(Key<RoadSign>(stopline.signid)).type;
// lane.waypoints.at(wp_idx + 1).wpstate.stopline_state = 1;
lane.waypoints.at(wp_idx).wpstate.stop_state = g_vmap.findByKey(Key<RoadSign>(stopline.signid)).type;
// lane.waypoints.at(wp_idx + 1).wpstate.stop_state = 1;
}
}
}
Expand All @@ -311,7 +311,7 @@ void DecisionMakerNode::callbackFromLaneWaypoint(const autoware_msgs::LaneArray
wp.wpstate.aid = 0;
wp.wpstate.steering_state = autoware_msgs::WaypointState::NULLSTATE;
wp.wpstate.accel_state = autoware_msgs::WaypointState::NULLSTATE;
wp.wpstate.stopline_state = autoware_msgs::WaypointState::NULLSTATE;
wp.wpstate.stop_state = autoware_msgs::WaypointState::NULLSTATE;
wp.wpstate.lanechange_state = autoware_msgs::WaypointState::NULLSTATE;
wp.wpstate.event_state = 0;
}
Expand Down Expand Up @@ -361,12 +361,12 @@ void DecisionMakerNode::callbackFromFinalWaypoint(const autoware_msgs::Lane &msg
{
if (i < current_finalwaypoints_.waypoints.size())
{
if (current_finalwaypoints_.waypoints.at(i).wpstate.stopline_state == autoware_msgs::WaypointState::TYPE_STOPLINE)
if (current_finalwaypoints_.waypoints.at(i).wpstate.stop_state == autoware_msgs::WaypointState::TYPE_STOPLINE)
{
ctx->setCurrentState(state_machine::DRIVE_ACC_STOPLINE_STATE);
closest_stopline_waypoint_ = CurrentStoplineTarget_.gid;
}
if (current_finalwaypoints_.waypoints.at(i).wpstate.stopline_state == autoware_msgs::WaypointState::TYPE_STOP)
if (current_finalwaypoints_.waypoints.at(i).wpstate.stop_state == autoware_msgs::WaypointState::TYPE_STOP)
ctx->setCurrentState(state_machine::DRIVE_ACC_STOP_STATE);
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -196,7 +196,7 @@ void DecisionMakerNode::updateLaneWaypointsArray(void)
for (auto& wp : lane.waypoints)
{
wp.twist.twist.linear.x = 0.0;
wp.wpstate.stopline_state = 0;
wp.wpstate.stop_state = 0;
}
}
for (auto& lane : current_shifted_lane_array_.lanes)
Expand All @@ -206,7 +206,7 @@ void DecisionMakerNode::updateLaneWaypointsArray(void)
// if stopped at stopline, to delete flags already used.
if (CurrentStoplineTarget_.gid - 2 <= wp.gid && wp.gid <= CurrentStoplineTarget_.gid + 2)
{
wp.wpstate.stopline_state = 0;
wp.wpstate.stop_state = 0;
}
}
}
Expand Down Expand Up @@ -262,7 +262,7 @@ void DecisionMakerNode::setAllStoplineStop(void)
b->x = lane.waypoints.at(wp_idx).pose.pose.position.x;
b->y = lane.waypoints.at(wp_idx).pose.pose.position.y;
if (amathutils::find_distance(a, b) <= 4) //
lane.waypoints.at(wp_idx).wpstate.stopline_state = 1;
lane.waypoints.at(wp_idx).wpstate.stop_state = 1;
}
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -139,7 +139,7 @@ void WaypointLoaderNode::saveLaneArray(const std::vector<std::string>& paths,
ofs << std::fixed << std::setprecision(4) << el.pose.pose.position.x << "," << el.pose.pose.position.y << ","
<< el.pose.pose.position.z << "," << tf::getYaw(el.pose.pose.orientation) << ","
<< mps2kmph(el.twist.twist.linear.x) << "," << (int)el.change_flag << "," << (int)el.wpstate.steering_state
<< "," << (int)el.wpstate.accel_state << "," << (int)el.wpstate.stopline_state << ","
<< "," << (int)el.wpstate.accel_state << "," << (int)el.wpstate.stop_state << ","
<< (int)el.wpstate.event_state << std::endl;
}
idx++;
Expand Down Expand Up @@ -294,7 +294,7 @@ void WaypointLoaderNode::parseWaypointForVer3(const std::string& line, const std
wp->change_flag = std::stoi(map["change_flag"]);
wp->wpstate.steering_state = (map.find("steering_flag") != map.end()) ? std::stoi(map["steering_flag"]) : 0;
wp->wpstate.accel_state = (map.find("accel_flag") != map.end()) ? std::stoi(map["accel_flag"]) : 0;
wp->wpstate.stopline_state = (map.find("stop_flag") != map.end()) ? std::stoi(map["stop_flag"]) : 0;
wp->wpstate.stop_state = (map.find("stop_flag") != map.end()) ? std::stoi(map["stop_flag"]) : 0;
wp->wpstate.event_state = (map.find("event_flag") != map.end()) ? std::stoi(map["event_flag"]) : 0;
}

Expand Down
23 changes: 17 additions & 6 deletions ros/src/msgs/autoware_msgs/msg/WaypointState.msg
Original file line number Diff line number Diff line change
@@ -1,16 +1,27 @@
int32 aid
uint8 NULLSTATE=0

# lanechange
uint8 lanechange_state

# bilinker
uint8 steering_state
uint8 STR_LEFT=1
uint8 STR_RIGHT=2
uint8 STR_STRAIGHT=3
uint8 STR_BACK=4

uint8 accel_state
uint8 stopline_state
uint8 TYPE_NULL=0
uint8 TYPE_STOPLINE=1
uint8 TYPE_STOP=2
# 1 is stopline, 2 is stop which 2 can only be released manually.
uint64 event_state

uint8 stop_state
# 1 is stopline, 2 is stop which can only be released manually.
uint8 TYPE_STOPLINE=1
uint8 TYPE_STOP=2

uint8 event_state
uint8 TYPE_EVENT_NULL = 0
uint8 TYPE_EVENT_GOAL = 1
uint8 TYPE_EVENT_MIDDLE_GOAL = 2
uint8 TYPE_EVENT_POSITION_STOP = 3
uint8 TYPE_EVENT_BUS_STOP = 4
uint8 TYPE_EVENT_PARKING = 5