Skip to content
Open
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
8 changes: 8 additions & 0 deletions fav/src/scenario/scenario_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -114,6 +114,11 @@ void ScenarioNode::ServeStart(
response->message = "Already running.";
return;
}
if (!initial_position_information_received_){
response->success = false;
response->message = "Current vehicle position still unknown.";
return;
}
Reset();
running_ = true;
using hippo_common::convert::EigenToRos;
Expand Down Expand Up @@ -300,6 +305,9 @@ void ScenarioNode::OnPose(
using hippo_common::convert::RosToEigen;
RosToEigen(_msg->pose.pose.position, vehicle_position_);
RosToEigen(_msg->pose.pose.orientation, vehicle_orientation_);
if (!initial_position_information_received_){
initial_position_information_received_ = true;
}

UpdateViewpointProgress();
viewpoint_index_.current = FindViewpointInTolerance();
Expand Down
1 change: 1 addition & 0 deletions fav/src/scenario/scenario_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,7 @@ class ScenarioNode : public rclcpp::Node {
bool running_{false};
bool start_position_reached_{false};
bool viewpoints_finished_{false};
bool initial_position_information_received_{false};
Eigen::Vector3d vehicle_position_;
Eigen::Quaterniond vehicle_orientation_;
ViewpointIndex viewpoint_index_;
Expand Down