Apollo 10.0
自动驾驶开放平台
apollo::dreamview::SimControlWithModelBase类 参考

#include <sim_control_with_model_base.h>

类 apollo::dreamview::SimControlWithModelBase 继承关系图:
apollo::dreamview::SimControlWithModelBase 的协作图:

Public 成员函数

 SimControlWithModelBase (const std::string &node_name)
 Construct a new Sim Control With Model Base object
 
void Start () override
 Starts the timer to publish simulated localization and chassis messages.
 
void Start (double x, double y, double v=0.0, double a=0.0) override
 Starts running the simulated control algorithm with position, e.g., publish simulated localization and chassis messages triggered by timer.
 
void ReSetPoinstion (double x, double y, double heading) override
 Set vehicle position.
 
void Stop () override
 Stops the algorithm.
 
void Reset () override
 Resets the internal state.
 
- Public 成员函数 继承自 apollo::dreamview::SimControlBase
virtual ~SimControlBase ()
 
virtual void RunOnce ()=0
 Main logic of the simulated control algorithm.
 
virtual void Init (bool set_start_point, nlohmann::json start_point_attr, bool use_start_point_position=false)=0
 Initialization.
 

Protected 成员函数

void InitTimerAndIO ()
 
void UpdateGearPosition ()
 
void InitStartPoint (nlohmann::json start_point_attr, bool use_start_point_position=false)
 
void InternalReset ()
 
void OnControlCommand (const apollo::control::ControlCommand &control_command)
 
void OnPlanningCommand (const std::shared_ptr< apollo::planning::PlanningCommand > &planning_command)
 
void OnPredictionObstacles (const std::shared_ptr< apollo::prediction::PredictionObstacles > &obstacles)
 
virtual void SetStartPoint (const ::apollo::sim_control::SimCarStatus &point)
 
void PublishChassis (const std::string model_name)
 pubish chassis info
 
void PublishLocalization (const std::string model_name)
 
void PublishDummyPrediction ()
 publish prediction info
 
- Protected 成员函数 继承自 apollo::dreamview::SimControlBase
void TransformToVRF (const apollo::common::Point3D &point_mrf, const apollo::common::Quaternion &orientation, apollo::common::Point3D *point_vrf)
 

Protected 属性

bool start_auto_ = false
 
bool auto_car_is_moving_ = false
 
bool planning_command_is_arrival_ = false
 
bool control_command_is_arrival_ = false
 
std::unique_ptr< cyber::Nodenode_
 
std::shared_ptr< cyber::Reader< apollo::control::ControlCommand > > control_command_reader_
 
std::shared_ptr< cyber::Reader< apollo::planning::PlanningCommand > > planning_command_reader_
 
std::shared_ptr< cyber::Reader< apollo::localization::LocalizationEstimate > > localization_reader_
 
std::shared_ptr< cyber::Reader< apollo::prediction::PredictionObstacles > > prediction_reader_
 
std::shared_ptr< cyber::Writer< apollo::canbus::Chassis > > chassis_writer_
 
std::shared_ptr< cyber::Writer< apollo::prediction::PredictionObstacles > > prediction_writer_
 
std::shared_ptr< cyber::Writer< apollo::localization::LocalizationEstimate > > localization_writer_
 
apollo::sim_control::SimCarStatus previous_point_
 
apollo::sim_control::SimCarStatus current_point_
 
apollo::control::ControlCommand control_cmd_
 
apollo::control::ControlCommand filtered_control_cmd_
 
apollo::common::Header current_routing_header_
 
apollo::common::PathPoint adc_position_
 
apollo::common::VehicleParam vehicle_param_
 
int gear_position_
 
double dt_
 
bool re_routing_triggered_ = false
 
bool send_dummy_prediction_ = true
 
MapServicemap_service_
 
- Protected 属性 继承自 apollo::dreamview::SimControlBase
std::unique_ptr< cyber::Timersim_control_timer_
 
std::unique_ptr< cyber::Timersim_prediction_timer_
 
std::mutex mutex_
 
bool enabled_ = false
 
bool start_point_from_localization_ = false
 
double start_velocity_ = 0.0
 
double start_acceleration_ = 0.0
 
double start_heading_ = std::numeric_limits<double>::max()
 

静态 Protected 属性

static constexpr double kModelIntervalMs = 10
 
static constexpr double kSimPredictionIntervalMs = 100
 

详细描述

在文件 sim_control_with_model_base.h52 行定义.

构造及析构函数说明

◆ SimControlWithModelBase()

apollo::dreamview::SimControlWithModelBase::SimControlWithModelBase ( const std::string &  node_name)
explicit

Construct a new Sim Control With Model Base object

Construct a new Sim Control With Model Base:: Sim Control With Model Base object

参数
node_name
node_namedepens on different dynamic model

在文件 sim_control_with_model_base.cc45 行定义.

成员函数说明

◆ InitStartPoint()

void apollo::dreamview::SimControlWithModelBase::InitStartPoint ( nlohmann::json  start_point_attr,
bool  use_start_point_position = false 
)
protected

在文件 sim_control_with_model_base.cc227 行定义.

228 {
229 AINFO << "Init start point with position!";
230
231 start_velocity_ = start_point_attr["start_velocity"];
232 start_acceleration_ = start_point_attr["start_acceleration"];
233 start_heading_ = start_point_attr["start_heading"];
234 SimCarStatus point;
235 localization_reader_->Observe();
237 if (use_start_point_position) {
238 // add start point position for dynamic model
239 // new add feature to keep same with simcontrol
240 point.set_x(start_point_attr["x"]);
241 point.set_y(start_point_attr["y"]);
242 // z use default 0
243 point.set_z(0);
244 double theta = 0.0;
245 double s = 0.0;
246 map_service_->GetPoseWithRegardToLane(start_point_attr["x"],
247 start_point_attr["y"], &theta, &s);
248 point.set_theta(theta);
249 point.set_speed(start_velocity_);
250 point.set_acceleration_s(start_acceleration_);
251 } else {
252 if (!localization_reader_->Empty()) {
253 const auto& pose = localization_reader_->GetLatestObserved()->pose();
254 auto x = pose.position().x();
255 auto y = pose.position().y();
256 auto z = pose.position().z();
257 if (map_service_->PointIsValid(x, y)) {
258 point.set_x(x);
259 point.set_y(y);
260 point.set_z(z);
261 point.set_theta(pose.heading());
262 point.set_speed(
263 std::hypot(pose.linear_velocity().x(), pose.linear_velocity().y()));
264 // Calculates the dot product of acceleration and velocity. The sign
265 // of this projection indicates whether this is acceleration or
266 // deceleration.
267 double projection =
268 pose.linear_acceleration().x() * pose.linear_velocity().x() +
269 pose.linear_acceleration().y() * pose.linear_velocity().y();
270
271 // Calculates the magnitude of the acceleration. Negate the value if
272 // it is indeed a deceleration.
273 double magnitude = std::hypot(pose.linear_acceleration().x(),
274 pose.linear_acceleration().y());
275 point.set_acceleration_s(std::signbit(projection) ? -magnitude
276 : magnitude);
277 // Set init gear to neutral position
278 point.set_gear_position(0);
280 }
281 }
283 apollo::common::PointENU start_point;
284 if (!map_service_->GetStartPoint(&start_point)) {
285 AWARN << "Failed to get a dummy start point from map!";
286 return;
287 }
288 point.set_x(start_point.x());
289 point.set_y(start_point.y());
290 point.set_z(start_point.z());
291 double theta = 0.0;
292 double s = 0.0;
293 map_service_->GetPoseWithRegardToLane(start_point.x(), start_point.y(),
294 &theta, &s);
295 point.set_theta(theta);
296 point.set_speed(start_velocity_);
297 point.set_acceleration_s(start_acceleration_);
298 AINFO << "start point from map default point"
299 << " x: " << start_point.x() << " y: " << start_point.y();
300 }
301 }
302 SetStartPoint(point);
303}
bool PointIsValid(const double x, const double y) const
bool GetStartPoint(apollo::common::PointENU *start_point) const
bool GetPoseWithRegardToLane(const double x, const double y, double *theta, double *s) const
std::shared_ptr< cyber::Reader< apollo::localization::LocalizationEstimate > > localization_reader_
virtual void SetStartPoint(const ::apollo::sim_control::SimCarStatus &point)
#define AINFO
Definition log.h:42
#define AWARN
Definition log.h:43

◆ InitTimerAndIO()

void apollo::dreamview::SimControlWithModelBase::InitTimerAndIO ( )
protected

在文件 sim_control_with_model_base.cc53 行定义.

53 {
54 // Setup control result data callback.
55 cyber::ReaderConfig control_cmd_reader_config;
56 control_cmd_reader_config.channel_name = FLAGS_control_command_topic;
57 control_cmd_reader_config.pending_queue_size =
58 FLAGS_reader_pending_queue_size;
59 prediction_reader_ = node_->CreateReader<PredictionObstacles>(
60 FLAGS_prediction_topic,
61 [this](const std::shared_ptr<PredictionObstacles>& obstacles) {
62 this->OnPredictionObstacles(obstacles);
63 });
64 planning_command_reader_ = node_->CreateReader<PlanningCommand>(
65 FLAGS_planning_command,
66 [this](const std::shared_ptr<PlanningCommand>& planning_command) {
67 this->OnPlanningCommand(planning_command);
68 });
69 control_command_reader_ = node_->CreateReader<ControlCommand>(
70 control_cmd_reader_config,
71 [this](const std::shared_ptr<ControlCommand>& cmd) {
72 ADEBUG << "Received control data: run canbus callback.";
73 OnControlCommand(*cmd);
74 });
75 // Setup localization callback.
76 cyber::ReaderConfig localization_reader_config;
77 localization_reader_config.channel_name = FLAGS_localization_topic;
78 localization_reader_config.pending_queue_size =
79 FLAGS_reader_pending_queue_size;
80 localization_reader_ = node_->CreateReader<LocalizationEstimate>(
81 localization_reader_config, nullptr);
82
84 node_->CreateWriter<LocalizationEstimate>(FLAGS_localization_topic);
85 chassis_writer_ = node_->CreateWriter<Chassis>(FLAGS_chassis_topic);
87 node_->CreateWriter<PredictionObstacles>(FLAGS_prediction_topic);
88
89 // Start timer to publish localization and chassis messages.
91 new cyber::Timer(kModelIntervalMs, [this]() { this->RunOnce(); }, false));
93 new cyber::Timer(kSimPredictionIntervalMs,
94 [this]() { this->PublishDummyPrediction(); }, false));
95}
std::unique_ptr< cyber::Timer > sim_control_timer_
std::unique_ptr< cyber::Timer > sim_prediction_timer_
virtual void RunOnce()=0
Main logic of the simulated control algorithm.
std::shared_ptr< cyber::Reader< apollo::planning::PlanningCommand > > planning_command_reader_
std::shared_ptr< cyber::Writer< apollo::localization::LocalizationEstimate > > localization_writer_
void OnControlCommand(const apollo::control::ControlCommand &control_command)
void OnPlanningCommand(const std::shared_ptr< apollo::planning::PlanningCommand > &planning_command)
void OnPredictionObstacles(const std::shared_ptr< apollo::prediction::PredictionObstacles > &obstacles)
std::shared_ptr< cyber::Reader< apollo::prediction::PredictionObstacles > > prediction_reader_
std::shared_ptr< cyber::Writer< apollo::prediction::PredictionObstacles > > prediction_writer_
std::shared_ptr< cyber::Writer< apollo::canbus::Chassis > > chassis_writer_
std::shared_ptr< cyber::Reader< apollo::control::ControlCommand > > control_command_reader_
#define ADEBUG
Definition log.h:41

◆ InternalReset()

◆ OnControlCommand()

void apollo::dreamview::SimControlWithModelBase::OnControlCommand ( const apollo::control::ControlCommand control_command)
protected

在文件 sim_control_with_model_base.cc191 行定义.

192 {
193 std::lock_guard<std::mutex> lock(mutex_);
194 if (!enabled_) {
195 return;
196 }
197 control_cmd_ = control_cmd;
199 (control_cmd_.throttle() >= 0.01 || control_cmd.brake() >= 0.01);
202}

◆ OnPlanningCommand()

void apollo::dreamview::SimControlWithModelBase::OnPlanningCommand ( const std::shared_ptr< apollo::planning::PlanningCommand > &  planning_command)
protected

在文件 sim_control_with_model_base.cc204 行定义.

205 {
206 std::lock_guard<std::mutex> lock(mutex_);
207 if (!enabled_) {
208 return;
209 }
210 // Avoid not sending prediction messages to planning after playing packets
211 // with obstacles
212 start_auto_ = true;
214 current_routing_header_ = planning_command->header();
215 AINFO << "planning_command: " << planning_command->DebugString();
219}

◆ OnPredictionObstacles()

void apollo::dreamview::SimControlWithModelBase::OnPredictionObstacles ( const std::shared_ptr< apollo::prediction::PredictionObstacles > &  obstacles)
protected

在文件 sim_control_with_model_base.cc109 行定义.

110 {
111 std::lock_guard<std::mutex> lock(mutex_);
112 if (!enabled_) {
113 return;
114 }
116 obstacles->header().module_name() == "SimDMPrediction";
117}

◆ PublishChassis()

void apollo::dreamview::SimControlWithModelBase::PublishChassis ( const std::string  model_name)
protected

pubish chassis info

参数
model_name

在文件 sim_control_with_model_base.cc310 行定义.

310 {
311 auto chassis = std::make_shared<Chassis>();
312 apollo::common::util::FillHeader(model_name, chassis.get());
313
314 chassis->set_engine_started(true);
315 chassis->set_speed_mps(current_point_.speed());
316 chassis->set_odometer_m(current_point_.odometer());
317
318 if (FLAGS_enable_steering_latency) {
319 chassis->set_steering_percentage(filtered_control_cmd_.steering_target());
320 } else {
321 chassis->set_steering_percentage(control_cmd_.steering_target());
322 }
323 chassis->set_throttle_percentage(control_cmd_.throttle());
324 chassis->set_brake_percentage(control_cmd_.brake());
325 if (start_auto_) {
326 chassis->set_driving_mode(Chassis::COMPLETE_AUTO_DRIVE);
327 } else {
328 chassis->set_driving_mode(Chassis::COMPLETE_MANUAL);
329 }
330 chassis->set_gear_location(control_cmd_.gear_location());
331 chassis_writer_->Write(chassis);
332}
optional apollo::canbus::Chassis::GearPosition gear_location

◆ PublishDummyPrediction()

void apollo::dreamview::SimControlWithModelBase::PublishDummyPrediction ( )
protected

publish prediction info

在文件 sim_control_with_model_base.cc338 行定义.

338 {
339 auto prediction = std::make_shared<PredictionObstacles>();
340 {
341 std::lock_guard<std::mutex> lock(mutex_);
343 return;
344 }
345 FillHeader("SimDMPrediction", prediction.get());
346 }
347 prediction_writer_->Write(prediction);
348}

◆ PublishLocalization()

void apollo::dreamview::SimControlWithModelBase::PublishLocalization ( const std::string  model_name)
protected

在文件 sim_control_with_model_base.cc350 行定义.

351 {
352 auto localization = std::make_shared<LocalizationEstimate>();
353 FillHeader(model_name, localization.get());
354
355 auto* pose = localization->mutable_pose();
356
357 // Set position
358 pose->mutable_position()->set_x(current_point_.x());
359 pose->mutable_position()->set_y(current_point_.y());
360 pose->mutable_position()->set_z(0.0);
361 // Set orientation and heading
362 double cur_theta = current_point_.theta();
363
364 Eigen::Quaternion<double> cur_orientation =
365 HeadingToQuaternion<double>(cur_theta);
366 ADEBUG << "cur_theta" << cur_theta;
367 ADEBUG << "cur_orientation_w" << cur_orientation.w() << "cur_orientation_x"
368 << cur_orientation.x() << "cur_orientation_y" << cur_orientation.y()
369 << "cur_orientation_z" << cur_orientation.z();
370 pose->mutable_orientation()->set_qw(cur_orientation.w());
371 pose->mutable_orientation()->set_qx(cur_orientation.x());
372 pose->mutable_orientation()->set_qy(cur_orientation.y());
373 pose->mutable_orientation()->set_qz(cur_orientation.z());
374 pose->set_heading(cur_theta);
375
376 // Set linear_velocity
378 pose->mutable_linear_velocity()->set_x(std::cos(cur_theta) * -1.0 *
380 pose->mutable_linear_velocity()->set_y(std::sin(cur_theta) * -1.0 *
382 } else {
383 pose->mutable_linear_velocity()->set_x(std::cos(cur_theta) *
385 pose->mutable_linear_velocity()->set_y(std::sin(cur_theta) *
387 }
388
389 pose->mutable_linear_velocity()->set_z(0);
390
391 // Set angular_velocity in both map reference frame and vehicle reference
392 // frame
393 double cur_curvature = std::tan(control_cmd_.steering_target() *
397
398 pose->mutable_angular_velocity()->set_x(0);
399 pose->mutable_angular_velocity()->set_y(0);
400 pose->mutable_angular_velocity()->set_z(current_point_.speed() *
401 cur_curvature);
402
403 TransformToVRF(pose->angular_velocity(), pose->orientation(),
404 pose->mutable_angular_velocity_vrf());
405
406 // Set linear_acceleration in both map reference frame and vehicle reference
407 // frame
408 auto* linear_acceleration = pose->mutable_linear_acceleration();
409 linear_acceleration->set_x(std::cos(cur_theta) *
411 linear_acceleration->set_y(std::sin(cur_theta) *
413 linear_acceleration->set_z(0);
414
415 TransformToVRF(pose->linear_acceleration(), pose->orientation(),
416 pose->mutable_linear_acceleration_vrf());
417
418 localization_writer_->Write(localization);
419
420 adc_position_.set_x(pose->position().x());
421 adc_position_.set_y(pose->position().y());
422 adc_position_.set_z(pose->position().z());
423}
void TransformToVRF(const apollo::common::Point3D &point_mrf, const apollo::common::Quaternion &orientation, apollo::common::Point3D *point_vrf)

◆ Reset()

void apollo::dreamview::SimControlWithModelBase::Reset ( )
overridevirtual

Resets the internal state.

实现了 apollo::dreamview::SimControlBase.

在文件 sim_control_with_model_base.cc177 行定义.

177 {
178 std::lock_guard<std::mutex> lock(mutex_);
180}

◆ ReSetPoinstion()

void apollo::dreamview::SimControlWithModelBase::ReSetPoinstion ( double  x,
double  y,
double  heading 
)
overridevirtual

Set vehicle position.

实现了 apollo::dreamview::SimControlBase.

在文件 sim_control_with_model_base.cc154 行定义.

155 {
156 std::lock_guard<std::mutex> lock(mutex_);
157 SimCarStatus point;
158 point.set_x(x);
159 point.set_y(y);
160 // z use default 0
161 point.set_z(0);
162 point.set_theta(heading);
163 SetStartPoint(point);
165}

◆ SetStartPoint()

void apollo::dreamview::SimControlWithModelBase::SetStartPoint ( const ::apollo::sim_control::SimCarStatus point)
protectedvirtual

在文件 sim_control_with_model_base.cc221 行定义.

221 {
222 previous_point_ = point;
223 auto_car_is_moving_ = false;
225}

◆ Start() [1/2]

void apollo::dreamview::SimControlWithModelBase::Start ( )
overridevirtual

Starts the timer to publish simulated localization and chassis messages.

实现了 apollo::dreamview::SimControlBase.

在文件 sim_control_with_model_base.cc119 行定义.

119 {
120 std::lock_guard<std::mutex> lock(mutex_);
121 if (!enabled_) {
123 // todo: Compatible with scenario conf and default value
124 Json start_point_attr({});
125 // start_point_attr:from scenario conf json or default value.here dm is
126 // divided from scenario use default value
127 start_point_attr["start_velocity"] = 0.0;
128 start_point_attr["start_acceleration"] = 0.0;
129 start_point_attr["start_heading"] = std::numeric_limits<double>::max();
130 Init(true, start_point_attr);
131 sim_control_timer_->Start();
132 sim_prediction_timer_->Start();
133 enabled_ = true;
134 }
135}
virtual void Init(bool set_start_point, nlohmann::json start_point_attr, bool use_start_point_position=false)=0
Initialization.
nlohmann::json Json

◆ Start() [2/2]

void apollo::dreamview::SimControlWithModelBase::Start ( double  x,
double  y,
double  v = 0.0,
double  a = 0.0 
)
overridevirtual

Starts running the simulated control algorithm with position, e.g., publish simulated localization and chassis messages triggered by timer.

实现了 apollo::dreamview::SimControlBase.

在文件 sim_control_with_model_base.cc137 行定义.

137 {
138 std::lock_guard<std::mutex> lock(mutex_);
139 if (!enabled_) {
141 Json start_point_attr({});
142 start_point_attr["start_velocity"] = v;
143 start_point_attr["start_acceleration"] = a;
144 start_point_attr["start_heading"] = std::numeric_limits<double>::max();
145 start_point_attr["x"] = x;
146 start_point_attr["y"] = y;
147 Init(true, start_point_attr, true);
148 sim_control_timer_->Start();
149 sim_prediction_timer_->Start();
150 enabled_ = true;
151 }
152}

◆ Stop()

void apollo::dreamview::SimControlWithModelBase::Stop ( )
overridevirtual

Stops the algorithm.

实现了 apollo::dreamview::SimControlBase.

在文件 sim_control_with_model_base.cc167 行定义.

167 {
168 std::lock_guard<std::mutex> lock(mutex_);
169
170 if (enabled_) {
171 sim_control_timer_->Stop();
172 sim_prediction_timer_->Stop();
173 enabled_ = false;
174 }
175}

◆ UpdateGearPosition()

void apollo::dreamview::SimControlWithModelBase::UpdateGearPosition ( )
protected

在文件 sim_control_with_model_base.cc97 行定义.

97 {
98 // update gear location, 1 drive, -1 reverse, 0 for other states
100 gear_position_ = 1;
102 gear_position_ = -1;
103 } else {
104 gear_position_ = 0;
105 }
106 current_point_.set_gear_position(gear_position_);
107}

类成员变量说明

◆ adc_position_

apollo::common::PathPoint apollo::dreamview::SimControlWithModelBase::adc_position_
protected

在文件 sim_control_with_model_base.h136 行定义.

◆ auto_car_is_moving_

bool apollo::dreamview::SimControlWithModelBase::auto_car_is_moving_ = false
protected

在文件 sim_control_with_model_base.h104 行定义.

◆ chassis_writer_

std::shared_ptr<cyber::Writer<apollo::canbus::Chassis> > apollo::dreamview::SimControlWithModelBase::chassis_writer_
protected

在文件 sim_control_with_model_base.h119 行定义.

◆ control_cmd_

apollo::control::ControlCommand apollo::dreamview::SimControlWithModelBase::control_cmd_
protected

在文件 sim_control_with_model_base.h128 行定义.

◆ control_command_is_arrival_

bool apollo::dreamview::SimControlWithModelBase::control_command_is_arrival_ = false
protected

在文件 sim_control_with_model_base.h106 行定义.

◆ control_command_reader_

std::shared_ptr<cyber::Reader<apollo::control::ControlCommand> > apollo::dreamview::SimControlWithModelBase::control_command_reader_
protected

在文件 sim_control_with_model_base.h111 行定义.

◆ current_point_

apollo::sim_control::SimCarStatus apollo::dreamview::SimControlWithModelBase::current_point_
protected

在文件 sim_control_with_model_base.h126 行定义.

◆ current_routing_header_

apollo::common::Header apollo::dreamview::SimControlWithModelBase::current_routing_header_
protected

在文件 sim_control_with_model_base.h134 行定义.

◆ dt_

double apollo::dreamview::SimControlWithModelBase::dt_
protected

在文件 sim_control_with_model_base.h142 行定义.

◆ filtered_control_cmd_

apollo::control::ControlCommand apollo::dreamview::SimControlWithModelBase::filtered_control_cmd_
protected

在文件 sim_control_with_model_base.h131 行定义.

◆ gear_position_

int apollo::dreamview::SimControlWithModelBase::gear_position_
protected

在文件 sim_control_with_model_base.h141 行定义.

◆ kModelIntervalMs

constexpr double apollo::dreamview::SimControlWithModelBase::kModelIntervalMs = 10
staticconstexprprotected

在文件 sim_control_with_model_base.h145 行定义.

◆ kSimPredictionIntervalMs

constexpr double apollo::dreamview::SimControlWithModelBase::kSimPredictionIntervalMs = 100
staticconstexprprotected

在文件 sim_control_with_model_base.h146 行定义.

◆ localization_reader_

std::shared_ptr<cyber::Reader<apollo::localization::LocalizationEstimate> > apollo::dreamview::SimControlWithModelBase::localization_reader_
protected

在文件 sim_control_with_model_base.h115 行定义.

◆ localization_writer_

std::shared_ptr<cyber::Writer<apollo::localization::LocalizationEstimate> > apollo::dreamview::SimControlWithModelBase::localization_writer_
protected

在文件 sim_control_with_model_base.h123 行定义.

◆ map_service_

MapService* apollo::dreamview::SimControlWithModelBase::map_service_
protected

在文件 sim_control_with_model_base.h153 行定义.

◆ node_

std::unique_ptr<cyber::Node> apollo::dreamview::SimControlWithModelBase::node_
protected

在文件 sim_control_with_model_base.h108 行定义.

◆ planning_command_is_arrival_

bool apollo::dreamview::SimControlWithModelBase::planning_command_is_arrival_ = false
protected

在文件 sim_control_with_model_base.h105 行定义.

◆ planning_command_reader_

std::shared_ptr<cyber::Reader<apollo::planning::PlanningCommand> > apollo::dreamview::SimControlWithModelBase::planning_command_reader_
protected

在文件 sim_control_with_model_base.h113 行定义.

◆ prediction_reader_

std::shared_ptr<cyber::Reader<apollo::prediction::PredictionObstacles> > apollo::dreamview::SimControlWithModelBase::prediction_reader_
protected

在文件 sim_control_with_model_base.h117 行定义.

◆ prediction_writer_

std::shared_ptr<cyber::Writer<apollo::prediction::PredictionObstacles> > apollo::dreamview::SimControlWithModelBase::prediction_writer_
protected

在文件 sim_control_with_model_base.h121 行定义.

◆ previous_point_

apollo::sim_control::SimCarStatus apollo::dreamview::SimControlWithModelBase::previous_point_
protected

在文件 sim_control_with_model_base.h125 行定义.

◆ re_routing_triggered_

bool apollo::dreamview::SimControlWithModelBase::re_routing_triggered_ = false
protected

在文件 sim_control_with_model_base.h149 行定义.

◆ send_dummy_prediction_

bool apollo::dreamview::SimControlWithModelBase::send_dummy_prediction_ = true
protected

在文件 sim_control_with_model_base.h152 行定义.

◆ start_auto_

bool apollo::dreamview::SimControlWithModelBase::start_auto_ = false
protected

在文件 sim_control_with_model_base.h103 行定义.

◆ vehicle_param_

apollo::common::VehicleParam apollo::dreamview::SimControlWithModelBase::vehicle_param_
protected

在文件 sim_control_with_model_base.h139 行定义.


该类的文档由以下文件生成: