18 float x()
const {
return f[0]; }
19 float y()
const {
return f[1]; }
20 float z()
const {
return f[2]; }
28 float x()
const {
return f[0]; }
29 float y()
const {
return f[1]; }
33 typedef std::array<point3d, 4>
object;
49 static void render_line(
const std::vector<pixel>&
line,
int color_code);
55 int main(
int argc,
char * argv[])
try 57 std::string out_map_filepath, in_map_filepath, default_filepath =
"map.raw";
58 for (
int c = 1;
c < argc; ++
c) {
59 if (!std::strcmp(argv[
c],
"-m") || !std::strcmp(argv[c],
"--load_map")) {
60 in_map_filepath = (++c < argc) ?
std::string(argv[c]) : default_filepath;
62 else if (!std::strcmp(argv[c],
"-s") || !std::strcmp(argv[c],
"--save_map")) {
63 out_map_filepath = (++c < argc) ?
std::string(argv[c]) : default_filepath;
67 " usages : [-m|--load_map IN_FILEPATH][-s|--save_map OUT_FILEPATH] \n" <<
68 " -m load raw map from IN_FILEPATH at start. \n" <<
69 " -s save raw map to OUT_FILEPATH at the end. \n";
73 std::cout <<
"Waiting for device..." << std::endl;
87 const float length = 0.20f;
88 const object virtual_object = { {
100 bool object_pose_in_world_initialized =
false;
106 if (!in_map_filepath.empty()) {
109 std::cout <<
"Map loaded from " << in_map_filepath << std::endl;
111 catch (std::runtime_error
e) {
std::cout << e.what() << std::endl; }
117 std::cout <<
"Relocalization Event Detected." << std::endl;
119 if (tm_sensor.get_static_node(virtual_object_guid, object_pose_in_world.
translation, object_pose_in_world.
rotation)) {
121 object_pose_in_world_initialized =
true;
130 const int fisheye_sensor_idx = 1;
138 std::cout <<
"Device got. Streaming data" << std::endl;
141 window app(intrinsics.
width, intrinsics.
height,
"Intel RealSense T265 Augmented Reality Example");
167 if (!object_pose_in_world_initialized && in_map_filepath.empty())
170 object_pose_in_world_initialized =
true;
181 object object_in_sensor;
182 for (
size_t i = 0;
i < object_in_device.size(); ++
i)
187 for (
size_t i = 1;
i < object_in_sensor.size(); ++
i)
190 std::vector<point3d> points_in_sensor =
raster_line(object_in_sensor[0], object_in_sensor[
i], 0.01
f);
191 std::vector<pixel> projected_line;
192 projected_line.reserve(points_in_sensor.size());
193 for (
auto&
point : points_in_sensor)
199 projected_line.emplace_back();
209 "Press spacebar to reset the pose of the virtual object. Press ESC to exit" :
210 "Move the camera around for saving the virtual object. Press ESC to exit" );
218 std::cout <<
"Setting new pose for virtual object: " << object_pose_in_world.
translation << std::endl;
222 if (tm_sensor.set_static_node(virtual_object_guid, object_pose_in_world.
translation, object_pose_in_world.
rotation)) {
223 std::cout <<
"Saved virtual object as static node. " << std::endl;
227 if (!out_map_filepath.empty()) {
230 std::cout <<
"Saved map to " << out_map_filepath << std::endl;
245 catch (
const std::exception& e)
280 return object_pose_in_world;
307 a.
x * b.
w + a.
w * b.
x - a.
z * b.
y + a.
y * b.
z,
308 a.
y * b.
w + a.
z * b.
x + a.
w * b.
y - a.
x * b.
z,
309 a.
z * b.
w - a.
y * b.
x + a.
x * b.
y + a.
w * b.
z,
310 a.
w * b.
w - a.
x * b.
x - a.
y * b.
y - a.
z * b.
z,
338 object transformed_obj;
339 for (
size_t i = 0;
i < obj.size(); ++
i) {
342 transformed_obj[
i].f[0] =
v.x;
343 transformed_obj[
i].f[1] =
v.y;
344 transformed_obj[
i].f[2] =
v.z;
346 return transformed_obj;
352 float distance = std::sqrt(direction.
x*direction.
x + direction.
y*direction.
y + direction.
z*direction.
z);
353 int npoints = (int)(distance / step + 1);
355 std::vector<point3d>
points;
362 points.reserve(npoints);
363 points.emplace_back(a);
364 for (
int i = 1;
i < npoints; ++
i)
366 points.emplace_back(a.
x() + direction.
x *
i,
367 a.
y() + direction.
y *
i,
368 a.
z() + direction.
z *
i);
383 color_code == 2 ? 1.f : 0.f,
384 color_code == 3 ? 1.f : 0.f);
387 for (
auto&
pixel : line)
403 draw_text(15, (win_height - 10) / 2, text.c_str());
412 throw std::runtime_error(
"Invalid binary file specified. Verify the target path and location permissions");
413 file.write((
char*)bytes.data(), bytes.size());
420 throw std::runtime_error(
"Invalid binary file specified. Verify the source path and location permissions");
424 std::size_t
size = file.tellg();
426 throw std::runtime_error(
"Invalid binary file -zero-size");
427 file.seekg(0, std::ios_base::beg);
430 std::vector<uint8_t>
v(size);
433 file.read((
char*)&v[0], size);
static rs2_quaternion quaternion_conjugate(const rs2_quaternion &q)
frameset wait_for_frames(unsigned int timeout_ms=RS2_DEFAULT_TIMEOUT) const
static void rs2_transform_point_to_point(float to_point[3], const struct rs2_extrinsics *extrin, const float from_point[3])
GLboolean GLboolean GLboolean b
void render(const rs2::frame &frame, const rect &rect, float alpha=1.f)
point3d(float x, float y, float z)
unsigned int tracker_confidence
static rs2_vector quaternion_rotate_vector(const rs2_quaternion &q, const rs2_vector &v)
rs2_extrinsics get_extrinsics_to(const stream_profile &to) const
static void render_text(int win_height, const std::string &text)
GLsizei const GLchar *const * string
std::array< point3d, 4 > object
static rs2_vector vector_negate(const rs2_vector &v)
GLsizei GLsizei GLfloat distance
rs2_pose get_pose_data() const
static rs2_vector vector_addition(const rs2_vector &a, const rs2_vector &b)
::realsense_legacy_msgs::pose_< std::allocator< void > > pose
GLboolean GLboolean GLboolean GLboolean a
Quaternion used to represent rotation.
const std::string & get_failed_args() const
static rs2_pose pose_inverse(const rs2_pose &p)
int main(int argc, char *argv[])
stream_profile get_stream(rs2_stream stream_type, int stream_index=-1) const
static std::vector< point3d > raster_line(const point3d &a, const point3d &b, float step)
static void render_line(const std::vector< pixel > &line, int color_code)
void enable_stream(rs2_stream stream_type, int stream_index, int width, int height, rs2_format format=RS2_FORMAT_ANY, int framerate=0)
static rs2_pose pose_multiply(const rs2_pose &ref2_in_ref1, const rs2_pose &ref3_in_ref2)
device get_device() const
rs2_notification_category get_category() const
static rs2_quaternion quaternion_multiply(const rs2_quaternion &a, const rs2_quaternion &b)
Cross-stream extrinsics: encodes the topology describing how the different devices are oriented...
3D vector in Euclidean coordinate space
static void rs2_project_point_to_pixel(float pixel[2], const struct rs2_intrinsics *intrin, const float point[3])
GLdouble GLdouble GLdouble q
pipeline_profile resolve(std::shared_ptr< rs2_pipeline > p) const
static rs2_pose identity_pose()
static rs2_vector pose_transform_point(const rs2_pose &pose, const rs2_vector &p)
const GLuint GLenum const void * binary
bool import_localization_map(const std::vector< uint8_t > &lmap_buf) const
void draw_text(int x, int y, const char *text)
GLenum GLuint GLenum GLsizei length
static object convert_object_coordinates(const object &obj, const rs2_pose &object_pose)
std::vector< uint8_t > bytes_from_raw_file(const std::string &filename)
void raw_file_from_bytes(const std::string &filename, const std::vector< uint8_t > bytes)
static rs2_pose reset_object_pose(const rs2_pose &device_pose_in_world=identity_pose())
const std::string & get_failed_function() const
GLdouble GLdouble GLint GLint const GLdouble * points