Functions | |
void | toCameraInfo (const TangoCameraIntrinsics &camera_intrinsics, sensor_msgs::CameraInfo *camera_info) |
void | toColor (const Tango3DR_Color &tango_color, std_msgs::ColorRGBA *color) |
std::string | toFrameId (const TangoCoordinateFrameType &tango_frame_type) |
void | toLaserScan (const TangoPointCloud &tango_point_cloud, double time_offset, double min_height, double max_height, double min_range, double max_range, const tf::Transform &point_cloud_T_laser, sensor_msgs::LaserScan *laser_scan) |
void | toLaserScanRange (double x, double y, double z, double min_height, double max_height, double min_range, double max_range, sensor_msgs::LaserScan *laser_scan) |
void | toMeshMarker (const Tango3DR_GridIndex &grid_index, const Tango3DR_Mesh &tango_mesh, double time_offset, const std::string &base_frame_id, visualization_msgs::Marker *mesh_marker) |
void | toOccupancyGrid (const Tango3DR_ImageBuffer &image_grid, const Tango3DR_Vector2 &origin, double time_offset, const std::string &base_frame_id, double resolution, uint8_t threshold, nav_msgs::OccupancyGrid *occupancy_grid) |
world coordinates (x: right, y: up). | |
void | toPoint (const Tango3DR_Vector3 &tango_vector, geometry_msgs::Point *point) |
void | toPointCloud2 (const TangoPointCloud &tango_point_cloud, double time_offset, sensor_msgs::PointCloud2 *point_cloud) |
void | toTango3DR_CameraCalibration (const TangoCameraIntrinsics &camera_intrinsics, Tango3DR_CameraCalibration *t3dr_camera_intrinsics) |
void | toTango3DR_Pose (const TangoPoseData &tango_pose_data, Tango3DR_Pose *t3dr_pose) |
void | toTransformStamped (const TangoPoseData &pose, double time_offset, const std::string &base_frame_id, const std::string &target_frame_id, geometry_msgs::TransformStamped *transform) |
Variables | |
constexpr int8_t | FREE_CELL = 0 |
const int | NUMBER_OF_FIELDS_IN_POINT_CLOUD = 4 |
constexpr int8_t | OCCUPIED_CELL = 100 |
constexpr int8_t | UNKNOWN_CELL = -1 |
void tango_ros_conversions_helper::toCameraInfo | ( | const TangoCameraIntrinsics & | camera_intrinsics, |
sensor_msgs::CameraInfo * | camera_info | ||
) |
Definition at line 172 of file tango_ros_conversions_helper.cpp.
void tango_ros_conversions_helper::toColor | ( | const Tango3DR_Color & | tango_color, |
std_msgs::ColorRGBA * | color | ||
) |
Definition at line 309 of file tango_ros_conversions_helper.cpp.
std::string tango_ros_conversions_helper::toFrameId | ( | const TangoCoordinateFrameType & | tango_frame_type | ) |
Definition at line 128 of file tango_ros_conversions_helper.cpp.
void tango_ros_conversions_helper::toLaserScan | ( | const TangoPointCloud & | tango_point_cloud, |
double | time_offset, | ||
double | min_height, | ||
double | max_height, | ||
double | min_range, | ||
double | max_range, | ||
const tf::Transform & | point_cloud_T_laser, | ||
sensor_msgs::LaserScan * | laser_scan | ||
) |
Definition at line 109 of file tango_ros_conversions_helper.cpp.
void tango_ros_conversions_helper::toLaserScanRange | ( | double | x, |
double | y, | ||
double | z, | ||
double | min_height, | ||
double | max_height, | ||
double | min_range, | ||
double | max_range, | ||
sensor_msgs::LaserScan * | laser_scan | ||
) |
Definition at line 73 of file tango_ros_conversions_helper.cpp.
void tango_ros_conversions_helper::toMeshMarker | ( | const Tango3DR_GridIndex & | grid_index, |
const Tango3DR_Mesh & | tango_mesh, | ||
double | time_offset, | ||
const std::string & | base_frame_id, | ||
visualization_msgs::Marker * | mesh_marker | ||
) |
Definition at line 222 of file tango_ros_conversions_helper.cpp.
void tango_ros_conversions_helper::toOccupancyGrid | ( | const Tango3DR_ImageBuffer & | image_grid, |
const Tango3DR_Vector2 & | origin, | ||
double | time_offset, | ||
const std::string & | base_frame_id, | ||
double | resolution, | ||
uint8_t | threshold, | ||
nav_msgs::OccupancyGrid * | occupancy_grid | ||
) |
world coordinates (x: right, y: up).
Definition at line 268 of file tango_ros_conversions_helper.cpp.
void tango_ros_conversions_helper::toPoint | ( | const Tango3DR_Vector3 & | tango_vector, |
geometry_msgs::Point * | point | ||
) |
Definition at line 303 of file tango_ros_conversions_helper.cpp.
void tango_ros_conversions_helper::toPointCloud2 | ( | const TangoPointCloud & | tango_point_cloud, |
double | time_offset, | ||
sensor_msgs::PointCloud2 * | point_cloud | ||
) |
Definition at line 42 of file tango_ros_conversions_helper.cpp.
void tango_ros_conversions_helper::toTango3DR_CameraCalibration | ( | const TangoCameraIntrinsics & | camera_intrinsics, |
Tango3DR_CameraCalibration * | t3dr_camera_intrinsics | ||
) |
Definition at line 197 of file tango_ros_conversions_helper.cpp.
void tango_ros_conversions_helper::toTango3DR_Pose | ( | const TangoPoseData & | tango_pose_data, |
Tango3DR_Pose * | t3dr_pose | ||
) |
Definition at line 213 of file tango_ros_conversions_helper.cpp.
void tango_ros_conversions_helper::toTransformStamped | ( | const TangoPoseData & | pose, |
double | time_offset, | ||
const std::string & | base_frame_id, | ||
const std::string & | target_frame_id, | ||
geometry_msgs::TransformStamped * | transform | ||
) |
Definition at line 24 of file tango_ros_conversions_helper.cpp.
constexpr int8_t tango_ros_conversions_helper::FREE_CELL = 0 |
Definition at line 31 of file tango_ros_conversions_helper.h.
Definition at line 30 of file tango_ros_conversions_helper.h.
constexpr int8_t tango_ros_conversions_helper::OCCUPIED_CELL = 100 |
Definition at line 32 of file tango_ros_conversions_helper.h.
constexpr int8_t tango_ros_conversions_helper::UNKNOWN_CELL = -1 |
Definition at line 33 of file tango_ros_conversions_helper.h.