Apollo  6.0
Open source self driving car software
pose.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2018 The Apollo Authors. All Rights Reserved.
3  *
4  * Licensed under the Apache License, Version 2.0 (the License);
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an AS IS BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *****************************************************************************/
16 #pragma once
17 
18 #include <map>
19 #include <string>
20 
21 #include "Eigen/Core"
22 
25 
26 namespace apollo {
27 namespace perception {
28 namespace camera {
29 
30 // @brief Car's Pose
31 class CarPose {
32  public:
33  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
34 
35  public:
36  CarPose() = default;
37  ~CarPose() = default;
38 
39  bool Init(double ts, const Eigen::Matrix4d& pose);
40 
41  const Eigen::Matrix4d getCarPose() const;
42  const Eigen::Vector3d getCarPosition() const;
43 
44  void ClearCameraPose(const std::string& camera_name);
45  void SetCameraPose(const std::string& camera_name,
46  const Eigen::Matrix4d& c2w_pose);
47  bool GetCameraPose(const std::string& camera_name,
48  Eigen::Matrix4d* c2w_pose) const;
49 
50  void setTimestamp(double ts) { timestamp_ = ts; }
51  double getTimestamp() const { return timestamp_; }
52 
53  Eigen::Matrix4d pose_; // car(novatel) to world pose
54  // camera to world poses
56  double timestamp_;
57 
58  private:
59  friend std::ostream& operator<<(std::ostream& os, const CarPose&);
60 };
61 
62 std::ostream& operator<<(std::ostream& os, const CarPose& pose);
63 
64 } // namespace camera
65 } // namespace perception
66 } // namespace apollo
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
void setTimestamp(double ts)
Definition: pose.h:50
Eigen::Vector3d Vector3d
Definition: frame_transform.h:27
Eigen::Matrix4d Matrix4d
Definition: base_map_fwd.h:32
std::map< T, EigenType, std::less< T >, Eigen::aligned_allocator< std::pair< const T, EigenType > >> EigenMap
Definition: eigen_defs.h:36
const Eigen::Vector3d getCarPosition() const
Eigen::Matrix4d pose_
Definition: pose.h:53
void SetCameraPose(const std::string &camera_name, const Eigen::Matrix4d &c2w_pose)
double getTimestamp() const
Definition: pose.h:51
friend std::ostream & operator<<(std::ostream &os, const CarPose &)
bool Init(double ts, const Eigen::Matrix4d &pose)
double timestamp_
Definition: pose.h:56
bool GetCameraPose(const std::string &camera_name, Eigen::Matrix4d *c2w_pose) const
void ClearCameraPose(const std::string &camera_name)
apollo::common::EigenMap< std::string, Eigen::Matrix4d > c2w_poses_
Definition: pose.h:55
const Eigen::Matrix4d getCarPose() const