Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Modified representations_example to getting IMU data from pcap and display #607

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
29 changes: 28 additions & 1 deletion examples/representations_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,9 @@

using namespace ouster;

const size_t UDP_BUF_SIZE = 65536;
auto packet_buf = std::make_unique<uint8_t[]>(UDP_BUF_SIZE);

//! [docs-stag-x-image-form]
img_t<double> get_x_in_image_form(const LidarScan& scan, bool destaggered,
const sensor::sensor_info& info) {
Expand Down Expand Up @@ -164,4 +167,28 @@ int main(int argc, char* argv[]) {
<< " and an x coordinate of "
<< x_image_destaggered(print_row, print_column) << "."
<< std::endl;
}

// 5. getting IMU
std::cerr << "\n5. Getting IMU data..." << std::endl;
sensor::packet_format pf = sensor::get_format(info);
ouster::sensor_utils::read_packet(*handle, packet_buf.get(), UDP_BUF_SIZE);
std::cout << "IMU Timestamp: " << pf.imu_gyro_ts(packet_buf.get()) << " ns" << std::endl;

const double standard_g = 9.80665;
auto linear_acceleration_x = pf.imu_la_x(packet_buf.get()) * standard_g;
auto linear_acceleration_y = pf.imu_la_y(packet_buf.get()) * standard_g;
auto linear_acceleration_z = pf.imu_la_z(packet_buf.get()) * standard_g;

auto angular_velocity_x = pf.imu_av_x(packet_buf.get()) * M_PI / 180.0;
auto angular_velocity_y = pf.imu_av_y(packet_buf.get()) * M_PI / 180.0;
auto angular_velocity_z = pf.imu_av_z(packet_buf.get()) * M_PI / 180.0;

std::cerr << "IMU Acceleration: ["
<< linear_acceleration_x << ", "
<< linear_acceleration_y << ", "
<< linear_acceleration_z << "] G" << std::endl;
std::cerr << "IMU Angular Velocity: ["
<< angular_velocity_x << ", "
<< angular_velocity_y << ", "
<< angular_velocity_z << "] deg/s" << std::endl;
}