Classes | Functions | Variables
astra_ros Namespace Reference

Classes

class  Device
 An agnostic C++ wrapper for the C Astra SDK. This object is wrapped by RosDevice. More...
 
class  Exception
 Wraps a astra_status_t when an Astra SDK call fails. More...
 
struct  Hsv
 
class  Nodelet
 
class  Parameter
 A "live" value that can be changed at runtime. Changes are broadcast to a listener. More...
 
class  ParameterImpl
 Internal implementation of a Parameter. More...
 
class  Rgb
 
class  Rgba
 A RGB color with alpha component. More...
 
class  RosDevice
 

Functions

std::vector< geometry_msgs::TransformStamped > bodyTransforms (const Body &body)
 
bool defaultMask (const std::size_t x, const std::size_t y)
 
double distance (const geometry_msgs::Point &lhs, const geometry_msgs::Point &rhs)
 
geometry_msgs::Transform fromEigen (const Eigen::Affine3d &transform)
 
geometry_msgs::Quaternion fromEigen (const Eigen::Quaterniond &quaternion)
 
geometry_msgs::Point fromEigen (const Eigen::Vector3d &point)
 
Device::ImageStreamMode fromRos (const ImageStreamMode &image_stream_mode)
 
Hsv indexColor (const std::size_t i)
 
Eigen::Quaterniond lookAt (const Eigen::Vector3d &source_point, const Eigen::Vector3d &dest_point, const Eigen::Vector3d &forward, const Eigen::Vector3d &up)
 
geometry_msgs::Point operator* (const geometry_msgs::Point &lhs, const geometry_msgs::Point &rhs)
 
geometry_msgs::Point operator+ (const geometry_msgs::Point &lhs, const geometry_msgs::Point &rhs)
 
geometry_msgs::Point operator- (const geometry_msgs::Point &lhs, const geometry_msgs::Point &rhs)
 
geometry_msgs::Point operator/ (const geometry_msgs::Point &lhs, const double rhs)
 
const std::string & statusToString (const astra_status_t status)
 
double sum (const geometry_msgs::Point &v)
 
Eigen::Vector3d toEigen (const geometry_msgs::Point &point)
 
Eigen::Quaterniond toEigen (const geometry_msgs::Quaternion &quaternion)
 
Eigen::Affine3d toEigen (const geometry_msgs::Transform &transform)
 
Eigen::Vector3d toEigen (const geometry_msgs::Vector3 &vector)
 
visualization_msgs::MarkerArray toMarkerArray (const Body &body)
 
visualization_msgs::MarkerArray toMarkerArray (const std::vector< Body > &bodies)
 
sensor_msgs::PointCloud toPointCloud (const sensor_msgs::Image &rgb, const sensor_msgs::Image &registered_depth, const sensor_msgs::CameraInfo &camera_info, const std::function< bool(const std::size_t x, const std::size_t y)> &mask=defaultMask)
 
std::vector< Body > toRos (const astra_body_list_t &body_list, const std_msgs::Header &header)
 
Body toRos (const astra_body_t &body, const std_msgs::Header &header)
 
sensor_msgs::Image toRos (const astra_floormask_t &floor_mask)
 
Plane toRos (const astra_plane_t &plane)
 
sensor_msgs::Image toRos (const astra_rgba_pixel_t *const data, const std::size_t length, const astra_image_metadata_t &metadata)
 
ImageStreamMode toRos (const Device::ImageStreamMode &image_stream_mode)
 
sensor_msgs::Image toRos (const std::int16_t *const data, const std::size_t length, const astra_image_metadata_t &metadata)
 
sensor_msgs::Image toRos (const std::uint8_t *const data, const std::size_t length, const astra_image_metadata_t &metadata)
 

Variables

const std::string DEVICE_NAMESPACE
 

Function Documentation

◆ bodyTransforms()

std::vector< geometry_msgs::TransformStamped > astra_ros::bodyTransforms ( const Body &  body)

Definition at line 90 of file tf.cpp.

◆ defaultMask()

bool astra_ros::defaultMask ( const std::size_t  x,
const std::size_t  y 
)

Definition at line 67 of file point_cloud.cpp.

◆ distance()

double astra_ros::distance ( const geometry_msgs::Point &  lhs,
const geometry_msgs::Point &  rhs 
)

Definition at line 12 of file math.cpp.

◆ fromEigen() [1/3]

geometry_msgs::Transform astra_ros::fromEigen ( const Eigen::Affine3d &  transform)

Definition at line 94 of file math.cpp.

◆ fromEigen() [2/3]

geometry_msgs::Quaternion astra_ros::fromEigen ( const Eigen::Quaterniond &  quaternion)

Definition at line 84 of file math.cpp.

◆ fromEigen() [3/3]

geometry_msgs::Point astra_ros::fromEigen ( const Eigen::Vector3d &  point)

Definition at line 75 of file math.cpp.

◆ fromRos()

Device::ImageStreamMode astra_ros::fromRos ( const ImageStreamMode &  image_stream_mode)

◆ indexColor()

Hsv astra_ros::indexColor ( const std::size_t  i)

Returns a unique color for a given integer i

Definition at line 291 of file color.cpp.

◆ lookAt()

Eigen::Quaterniond astra_ros::lookAt ( const Eigen::Vector3d &  source_point,
const Eigen::Vector3d &  dest_point,
const Eigen::Vector3d &  forward,
const Eigen::Vector3d &  up 
)

Definition at line 115 of file math.cpp.

◆ operator*()

geometry_msgs::Point astra_ros::operator* ( const geometry_msgs::Point &  lhs,
const geometry_msgs::Point &  rhs 
)

Definition at line 36 of file math.cpp.

◆ operator+()

geometry_msgs::Point astra_ros::operator+ ( const geometry_msgs::Point &  lhs,
const geometry_msgs::Point &  rhs 
)

Definition at line 18 of file math.cpp.

◆ operator-()

geometry_msgs::Point astra_ros::operator- ( const geometry_msgs::Point &  lhs,
const geometry_msgs::Point &  rhs 
)

Definition at line 27 of file math.cpp.

◆ operator/()

geometry_msgs::Point astra_ros::operator/ ( const geometry_msgs::Point &  lhs,
const double  rhs 
)

Definition at line 45 of file math.cpp.

◆ statusToString()

const std::string & astra_ros::statusToString ( const astra_status_t  status)

Definition at line 68 of file util.cpp.

◆ sum()

double astra_ros::sum ( const geometry_msgs::Point &  v)

Definition at line 7 of file math.cpp.

◆ toEigen() [1/4]

Eigen::Vector3d astra_ros::toEigen ( const geometry_msgs::Point &  point)

Definition at line 54 of file math.cpp.

◆ toEigen() [2/4]

Eigen::Quaterniond astra_ros::toEigen ( const geometry_msgs::Quaternion &  quaternion)

Definition at line 64 of file math.cpp.

◆ toEigen() [3/4]

Eigen::Affine3d astra_ros::toEigen ( const geometry_msgs::Transform &  transform)

Definition at line 69 of file math.cpp.

◆ toEigen() [4/4]

Eigen::Vector3d astra_ros::toEigen ( const geometry_msgs::Vector3 &  vector)

Definition at line 59 of file math.cpp.

◆ toMarkerArray() [1/2]

visualization_msgs::MarkerArray astra_ros::toMarkerArray ( const Body &  body)

◆ toMarkerArray() [2/2]

visualization_msgs::MarkerArray astra_ros::toMarkerArray ( const std::vector< Body > &  bodies)

◆ toPointCloud()

sensor_msgs::PointCloud astra_ros::toPointCloud ( const sensor_msgs::Image &  rgb,
const sensor_msgs::Image &  registered_depth,
const sensor_msgs::CameraInfo &  camera_info,
const std::function< bool(const std::size_t x, const std::size_t y)> &  mask = defaultMask 
)

Definition at line 72 of file point_cloud.cpp.

◆ toRos() [1/8]

std::vector< astra_ros::Body > astra_ros::toRos ( const astra_body_list_t &  body_list,
const std_msgs::Header header 
)

Definition at line 201 of file util.cpp.

◆ toRos() [2/8]

astra_ros::Body astra_ros::toRos ( const astra_body_t &  body,
const std_msgs::Header header 
)

Definition at line 145 of file util.cpp.

◆ toRos() [3/8]

sensor_msgs::Image astra_ros::toRos ( const astra_floormask_t &  floor_mask)

Definition at line 126 of file util.cpp.

◆ toRos() [4/8]

astra_ros::Plane astra_ros::toRos ( const astra_plane_t &  plane)

Definition at line 213 of file util.cpp.

◆ toRos() [5/8]

sensor_msgs::Image astra_ros::toRos ( const astra_rgba_pixel_t *const  data,
const std::size_t  length,
const astra_image_metadata_t &  metadata 
)

Definition at line 103 of file util.cpp.

◆ toRos() [6/8]

astra_ros::ImageStreamMode astra_ros::toRos ( const Device::ImageStreamMode image_stream_mode)

Definition at line 224 of file util.cpp.

◆ toRos() [7/8]

sensor_msgs::Image astra_ros::toRos ( const std::int16_t *const  data,
const std::size_t  length,
const astra_image_metadata_t &  metadata 
)

Definition at line 89 of file util.cpp.

◆ toRos() [8/8]

sensor_msgs::Image astra_ros::toRos ( const std::uint8_t *const  data,
const std::size_t  length,
const astra_image_metadata_t &  metadata 
)

Definition at line 75 of file util.cpp.

Variable Documentation

◆ DEVICE_NAMESPACE

const std::string astra_ros::DEVICE_NAMESPACE


astra_ros
Author(s): Braden McDorman
autogenerated on Wed Mar 2 2022 00:53:06