Apollo 10.0
自动驾驶开放平台
apollo::perception::onboard 命名空间参考

struct  CameraFrame
 
class  CameraFrameMessage
 
class  Descriptor
 
struct  LaneDetection
 
class  LaneDetectionComponent
 
class  LidarFrameMessage
 
struct  MotionServiceComponent
 
class  MsgBuffer
 
class  MsgSerializer
 
class  SensorFrameMessage
 
struct  StampedTransform
 
class  TrafficDetectMessage
 
class  TransformCache
 
class  TransformWrapper
 

类型定义

typedef FunctionInfo< LaneDetectionComponentFunInfoType
 

枚举

enum class  ProcessStage {
  LIDAR_PREPROCESS = 0 , LIDAR_DETECTION = 1 , LIDAR_RECOGNITION = 2 , STEREO_CAMERA_DETECTION = 3 ,
  MONOCULAR_CAMERA_DETECTION = 4 , LONG_RANGE_RADAR_DETECTION = 5 , SHORT_RANGE_RADAR_DETECTION = 6 , ULTRASONIC_DETECTION = 7 ,
  SENSOR_FUSION = 8 , UNKNOWN_STAGE = 9 , PROCESSSTAGE_COUNT = 10
}
 

函数

 DEFINE_bool (obs_enable_hdmap_input, true, "enable hdmap input for roi filter")
 
 DEFINE_bool (obs_enable_visualization, false, "whether to send message for visualization")
 
 DEFINE_string (obs_screen_output_dir, "./", "output dir. for saving visualization screenshots")
 
 DEFINE_bool (obs_benchmark_mode, false, "whether open benchmark mode, default false")
 
 DEFINE_bool (obs_save_fusion_supplement, false, "whether save fusion supplement data, default false")
 
 DEFINE_bool (start_visualizer, false, "Whether to start visualizer")
 
 DECLARE_bool (obs_enable_hdmap_input)
 
 DECLARE_bool (obs_enable_visualization)
 
 DECLARE_string (obs_screen_output_dir)
 
 DECLARE_bool (obs_benchmark_mode)
 
 DECLARE_bool (obs_save_fusion_supplement)
 
 DECLARE_bool (start_visualizer)
 
 DEFINE_int32 (obs_msg_buffer_size, 200, "buffer size for odometry_subscriber")
 
 DEFINE_double (obs_buffer_match_precision, 0.01, "match_precision for odometry_subscriber")
 
 DECLARE_int32 (obs_msg_buffer_size)
 
 DECLARE_double (obs_buffer_match_precision)
 
 DEFINE_string (obs_sensor2novatel_tf2_frame_id, "novatel", "sensor to novatel frame id")
 
 DEFINE_string (obs_novatel2world_tf2_frame_id, "world", "novatel to world frame id")
 
 DEFINE_string (obs_novatel2world_tf2_child_frame_id, "novatel", "novatel to world child frame id")
 
 DEFINE_double (obs_tf2_buff_size, 0.01, "query Cyber TF buffer size in second")
 
 DEFINE_double (obs_transform_cache_size, 1.0, "transform cache size in second")
 
 DEFINE_double (obs_max_local_pose_extrapolation_latency, 0.15, "max local pose extrapolation period in second")
 
 DEFINE_bool (obs_enable_local_pose_extrapolation, true, "use local pose extrapolation")
 
 DEFINE_bool (hardware_trigger, true, "camera trigger method")
 
Eigen::Quaterniond Slerp (const Eigen::Quaterniond &source, const double &t, const Eigen::Quaterniond &other)
 
 DECLARE_string (obs_sensor2novatel_tf2_frame_id)
 
 DECLARE_string (obs_novatel2world_tf2_frame_id)
 
 DECLARE_string (obs_novatel2world_tf2_child_frame_id)
 
 DECLARE_double (obs_tf2_buff_size)
 
 DECLARE_bool (hardware_trigger)
 
 CYBER_REGISTER_COMPONENT (LaneDetectionComponent)
 

类型定义说明

◆ FunInfoType

枚举类型说明

◆ ProcessStage

枚举值
LIDAR_PREPROCESS 
LIDAR_DETECTION 
LIDAR_RECOGNITION 
STEREO_CAMERA_DETECTION 
MONOCULAR_CAMERA_DETECTION 
LONG_RANGE_RADAR_DETECTION 
SHORT_RANGE_RADAR_DETECTION 
ULTRASONIC_DETECTION 
SENSOR_FUSION 
UNKNOWN_STAGE 
PROCESSSTAGE_COUNT 

在文件 inner_component_messages.h30 行定义.

函数说明

◆ CYBER_REGISTER_COMPONENT()

apollo::perception::onboard::CYBER_REGISTER_COMPONENT ( LaneDetectionComponent  )

◆ DECLARE_bool() [1/6]

apollo::perception::onboard::DECLARE_bool ( hardware_trigger  )

◆ DECLARE_bool() [2/6]

apollo::perception::onboard::DECLARE_bool ( obs_benchmark_mode  )

◆ DECLARE_bool() [3/6]

apollo::perception::onboard::DECLARE_bool ( obs_enable_hdmap_input  )

◆ DECLARE_bool() [4/6]

apollo::perception::onboard::DECLARE_bool ( obs_enable_visualization  )

◆ DECLARE_bool() [5/6]

apollo::perception::onboard::DECLARE_bool ( obs_save_fusion_supplement  )

◆ DECLARE_bool() [6/6]

apollo::perception::onboard::DECLARE_bool ( start_visualizer  )

◆ DECLARE_double() [1/2]

apollo::perception::onboard::DECLARE_double ( obs_buffer_match_precision  )

◆ DECLARE_double() [2/2]

apollo::perception::onboard::DECLARE_double ( obs_tf2_buff_size  )

◆ DECLARE_int32()

apollo::perception::onboard::DECLARE_int32 ( obs_msg_buffer_size  )

◆ DECLARE_string() [1/4]

apollo::perception::onboard::DECLARE_string ( obs_novatel2world_tf2_child_frame_id  )

◆ DECLARE_string() [2/4]

apollo::perception::onboard::DECLARE_string ( obs_novatel2world_tf2_frame_id  )

◆ DECLARE_string() [3/4]

apollo::perception::onboard::DECLARE_string ( obs_screen_output_dir  )

◆ DECLARE_string() [4/4]

apollo::perception::onboard::DECLARE_string ( obs_sensor2novatel_tf2_frame_id  )

◆ DEFINE_bool() [1/7]

apollo::perception::onboard::DEFINE_bool ( hardware_trigger  ,
true  ,
"camera trigger method"   
)

◆ DEFINE_bool() [2/7]

apollo::perception::onboard::DEFINE_bool ( obs_benchmark_mode  ,
false  ,
"whether open benchmark  mode,
default false"   
)

◆ DEFINE_bool() [3/7]

apollo::perception::onboard::DEFINE_bool ( obs_enable_hdmap_input  ,
true  ,
"enable hdmap input for roi filter"   
)

◆ DEFINE_bool() [4/7]

apollo::perception::onboard::DEFINE_bool ( obs_enable_local_pose_extrapolation  ,
true  ,
"use local pose extrapolation"   
)

◆ DEFINE_bool() [5/7]

apollo::perception::onboard::DEFINE_bool ( obs_enable_visualization  ,
false  ,
"whether to send message for visualization"   
)

◆ DEFINE_bool() [6/7]

apollo::perception::onboard::DEFINE_bool ( obs_save_fusion_supplement  ,
false  ,
"whether save fusion supplement  data,
default false"   
)

◆ DEFINE_bool() [7/7]

apollo::perception::onboard::DEFINE_bool ( start_visualizer  ,
false  ,
"Whether to start visualizer"   
)

◆ DEFINE_double() [1/4]

apollo::perception::onboard::DEFINE_double ( obs_buffer_match_precision  ,
0.  01,
"match_precision for odometry_subscriber"   
)

◆ DEFINE_double() [2/4]

apollo::perception::onboard::DEFINE_double ( obs_max_local_pose_extrapolation_latency  ,
0.  15,
"max local pose extrapolation period in second"   
)

◆ DEFINE_double() [3/4]

apollo::perception::onboard::DEFINE_double ( obs_tf2_buff_size  ,
0.  01,
"query Cyber TF buffer size in second"   
)

◆ DEFINE_double() [4/4]

apollo::perception::onboard::DEFINE_double ( obs_transform_cache_size  ,
1.  0,
"transform cache size in second"   
)

◆ DEFINE_int32()

apollo::perception::onboard::DEFINE_int32 ( obs_msg_buffer_size  ,
200  ,
"buffer size for odometry_subscriber"   
)

◆ DEFINE_string() [1/4]

apollo::perception::onboard::DEFINE_string ( obs_novatel2world_tf2_child_frame_id  ,
"novatel"  ,
"novatel to world child frame id"   
)

◆ DEFINE_string() [2/4]

apollo::perception::onboard::DEFINE_string ( obs_novatel2world_tf2_frame_id  ,
"world"  ,
"novatel to world frame id"   
)

◆ DEFINE_string() [3/4]

apollo::perception::onboard::DEFINE_string ( obs_screen_output_dir  ,
"./"  ,
"output dir. for saving visualization screenshots"   
)

◆ DEFINE_string() [4/4]

apollo::perception::onboard::DEFINE_string ( obs_sensor2novatel_tf2_frame_id  ,
"novatel"  ,
"sensor to novatel frame id"   
)

◆ Slerp()

Eigen::Quaterniond apollo::perception::onboard::Slerp ( const Eigen::Quaterniond &  source,
const double &  t,
const Eigen::Quaterniond &  other 
)

在文件 transform_wrapper.cc64 行定义.

65 {
66 const double one = 1.0 - std::numeric_limits<double>::epsilon();
67 double d = source.x() * other.x() + source.y() * other.y() +
68 source.z() * other.z() + source.w() * other.w();
69 double abs_d = std::abs(d);
70
71 double scale0;
72 double scale1;
73
74 if (abs_d >= one) {
75 scale0 = 1.0 - t;
76 scale1 = t;
77 } else {
78 // theta is the angle between the 2 quaternions
79 double theta = std::acos(abs_d);
80 double sin_theta = std::sin(theta);
81
82 scale0 = std::sin((1.0 - t) * theta) / sin_theta;
83 scale1 = std::sin((t * theta)) / sin_theta;
84 }
85 if (d < 0) scale1 = -scale1;
86
87 return Eigen::Quaterniond(scale0 * source.w() + scale1 * other.w(),
88 scale0 * source.x() + scale1 * other.x(),
89 scale0 * source.y() + scale1 * other.y(),
90 scale0 * source.z() + scale1 * other.z());
91}