include
ensenso_camera
conversion.h
Go to the documentation of this file.
1
#pragma once
2
3
#include "
ensenso_camera/ros2/namespace.h
"
4
5
#include "
ensenso_camera/ros2/geometry_msgs/point32.h
"
6
7
#include "nxLib.h"
8
9
namespace
ensenso_conversion
10
{
11
double
nxLibToRosTimestamp
(
double
const
& timestamp,
bool
isFileCamera =
false
);
12
13
double
nxLibToPclTimestamp
(
double
const
& timestamp,
bool
isFileCamera =
false
);
14
15
// Internally units are used with millimeters instead of meters, but ROS uses meters most often.
16
const
int
conversionFactor
= 1000;
17
18
geometry_msgs::msg::Point32
toRosPoint
(NxLibItem
const
& itemArray,
bool
convertUnits =
true
);
19
20
NxLibItem
toEnsensoPoint
(geometry_msgs::msg::Point32
const
& point,
bool
convertUnits =
true
);
21
22
}
// namespace ensenso_conversion
ensenso_conversion::nxLibToPclTimestamp
double nxLibToPclTimestamp(double const ×tamp, bool isFileCamera=false)
Definition:
conversion.cpp:45
namespace.h
ensenso_conversion
Definition:
conversion.h:9
point32.h
ensenso_conversion::conversionFactor
const int conversionFactor
Definition:
conversion.h:16
ensenso_conversion::toRosPoint
geometry_msgs::msg::Point32 toRosPoint(NxLibItem const &itemArray, bool convertUnits=true)
Definition:
conversion.cpp:51
ensenso_conversion::nxLibToRosTimestamp
double nxLibToRosTimestamp(double const ×tamp, bool isFileCamera=false)
Definition:
conversion.cpp:40
ensenso_conversion::toEnsensoPoint
NxLibItem toEnsensoPoint(geometry_msgs::msg::Point32 const &point, bool convertUnits=true)
Definition:
conversion.cpp:70
ensenso_camera
Author(s): Ensenso
autogenerated on Wed Apr 2 2025 02:37:46