25 #include "Eigen/Dense" 26 #include "Eigen/Eigen" 27 #include "Eigen/Geometry" 31 namespace perception {
42 std::list<base::VehicleStatus> raw_motion_queue_;
47 float time_difference_;
51 void generate_motion_matrix(
53 void accumulate_motion(
double start_time,
double end_time);
55 const double pre_image_timestamp,
56 const double image_timestamp);
60 if (mot_buffer_ !=
nullptr) {
62 mot_buffer_ =
nullptr;
65 mat_motion_sensor_ = base::MotionType::Identity();
72 if (mot_buffer_ ==
nullptr) {
75 mot_buffer_->set_capacity(buffer_size_);
79 void add_new_motion(
double pre_image_timestamp,
double image_timestamp,
80 int motion_operation_flag,
void cleanbuffer()
Definition: plane_motion.h:59
base::MotionBuffer get_buffer()
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
Definition: plane_motion.h:34
Definition: plane_motion.h:39
Eigen::Matrix4f MotionType
Definition: object_supplement.h:188
void add_new_motion(double pre_image_timestamp, double image_timestamp, int motion_operation_flag, base::VehicleStatus *vehicledata)
bool find_motion_with_timestamp(double timestamp, base::VehicleStatus *vs)
Definition: object_supplement.h:189
bool is_3d_motion() const
Definition: plane_motion.h:85
Definition: plane_motion.h:39
std::shared_ptr< MotionBuffer > MotionBufferPtr
Definition: object_supplement.h:203
void set_buffer_size(int s)
Definition: plane_motion.h:68
Definition: plane_motion.h:39
Definition: plane_motion.h:39
boost::circular_buffer< VehicleStatus > MotionBuffer
Definition: object_supplement.h:202