Skip to content

Commit

Permalink
update
Browse files Browse the repository at this point in the history
  • Loading branch information
chao committed May 24, 2021
1 parent 22ac0b1 commit 0b15356
Show file tree
Hide file tree
Showing 4 changed files with 30 additions and 29 deletions.
2 changes: 2 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -30,3 +30,5 @@
*.exe
*.out
*.app

build/
9 changes: 4 additions & 5 deletions .vscode/c_cpp_properties.json
Original file line number Diff line number Diff line change
Expand Up @@ -8,11 +8,10 @@
"/usr/include/pcl-1.10",
"/usr/local/include/eigen3",
"/usr/local/include/opencv4",
"/opt/arrayfire/include",
"/home/chao/Workspace/ws/ouster_ws/devel/include",
"/home/chao/Workspace/ws/ouster_ws/src/ouster_example/ouster_ros/include",
"/home/chao/Workspace/ws/ouster_ws/src/ouster_example/ouster_client/include",
"/home/chao/Workspace/ws/ouster_ws/src/ouster_example/ouster_client/include/optional-lite"
"~/Workspace/ws/ouster_ws/devel/include",
"~/Workspace/ws/ouster_ws/src/ouster_example/ouster_ros/include",
"~/Workspace/ws/ouster_ws/src/ouster_example/ouster_client/include",
"~/Workspace/ws/ouster_ws/src/ouster_example/ouster_client/include/optional-lite"
],
"defines": [],
"compilerPath": "/usr/bin/g++"
Expand Down
15 changes: 8 additions & 7 deletions src/decoder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,8 +60,8 @@ void LidarModel::ToCameraInfo(sensor_msgs::CameraInfo& cinfo) {
cinfo.D.insert(cinfo.D.end(), altitudes.begin(), altitudes.end());
cinfo.D.insert(cinfo.D.end(), azimuths.begin(), azimuths.end());

cinfo.K[0] = dt_meas; // delta time between two columns
cinfo.R[0] = d_azimuth; // delta angle between two columns
cinfo.K[0] = dt_meas;
cinfo.R[0] = d_azimuth;
cinfo.P[0] = beam_offset;
}

Expand Down Expand Up @@ -170,11 +170,12 @@ void Decoder::Reset() {
if (curr_scan_ * image_.cols >= model_.cols) {
curr_scan_ = 0;
}
// No need to zero out if we don't need to destagger
if (!destagger_) return;
// Otherwise we will zero out the cached data
image_.setTo(cv::Scalar());
// TODO (chao): set cloud_ to 0

if (destagger_) {
// Zero out cached image in destagger mode
image_.setTo(cv::Scalar());
// No need for cloud since we set invalid point to nan
}
}

void Decoder::Allocate(int rows, int cols) {
Expand Down
33 changes: 16 additions & 17 deletions src/decoder.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,12 +13,12 @@
namespace ouster_decoder {

struct LidarData {
float range{}; // range in meter
float theta{}; // azimuth angle
uint16_t shift{}; // pixel shift
uint16_t signal{};
uint16_t ambient{};
uint16_t reflectivity{};
float range{}; // range in meter
float theta{}; // azimuth angle
uint16_t shift{}; // pixel shift
uint16_t signal{}; // signal intensity photon
uint16_t ambient{}; // NIR photons
uint16_t reflectivity{}; // calibrated reflectivity
} __attribute__((packed));

static_assert(sizeof(LidarData) == sizeof(float) * 4,
Expand All @@ -28,17 +28,16 @@ struct LidarModel {
LidarModel() = default;
explicit LidarModel(const ouster_ros::sensor::sensor_info& info);

int rows;
int cols; // cols of a full scan
int freq;
double dt_meas;
double dt_packet;
double d_azimuth;
double beam_offset;
std::vector<double> azimuths;
std::vector<double> altitudes;
std::vector<int> pixel_shifts;
std::string prod_line;
int rows{}; // number of beams
int cols{}; // cols of a full scan
int freq{}; // frequency
double dt_meas{}; // delta time between two columns
double d_azimuth{}; // delta angle between two columns
double beam_offset{}; // distance between beam to origin
std::vector<double> azimuths; // azimuths offset angles
std::vector<double> altitudes; // altitude angles, high to low
std::vector<int> pixel_shifts; // offset pixel count
std::string prod_line; // produnction line

void ToCameraInfo(sensor_msgs::CameraInfo& cinfo);
};
Expand Down

0 comments on commit 0b15356

Please sign in to comment.