Public Member Functions | Private Member Functions | Private Attributes
tango_ros_native::TangoRosNodelet Class Reference

#include <tango_ros_nodelet.h>

Inheritance diagram for tango_ros_native::TangoRosNodelet:
Inheritance graph
[legend]

List of all members.

Public Member Functions

bool GetAvailableMapUuidsList (std::vector< std::string > &uuid_list)
bool GetMapNameFromUuid (const std::string &map_uuid, std::string &map_name)
void OnFrameAvailable (TangoCameraId camera_id, const TangoImageBuffer *buffer)
void onInit ()
void OnPointCloudAvailable (const TangoPointCloud *point_cloud)
void OnPoseAvailable (const TangoPoseData *pose)
TangoErrorType OnTangoServiceConnected ()
void StartPublishing ()
void StopPublishing ()
void TangoDisconnect ()
 TangoRosNodelet ()
 ~TangoRosNodelet ()

Private Member Functions

TangoErrorType ConnectToTangoAndSetUpNode ()
void DynamicReconfigureCallback (PublisherConfig &config, uint32_t level)
bool GetMapNameServiceCallback (const tango_ros_messages::GetMapName::Request &req, tango_ros_messages::GetMapName::Response &res)
bool GetMapUuidsServiceCallback (const tango_ros_messages::GetMapUuids::Request &req, tango_ros_messages::GetMapUuids::Response &res)
bool LoadOccupancyGridServiceCallback (const tango_ros_messages::LoadOccupancyGrid::Request &req, tango_ros_messages::LoadOccupancyGrid::Response &res)
void PublishColorImage ()
void PublishDevicePose ()
void PublishFisheyeImage ()
void PublishLaserScan ()
void PublishMesh ()
void PublishPointCloud ()
void PublishStaticTransforms ()
void RunRosSpin ()
bool SaveMapServiceCallback (const tango_ros_messages::SaveMap::Request &req, tango_ros_messages::SaveMap::Response &res)
TangoErrorType TangoConnect ()
bool TangoConnectServiceCallback (const tango_ros_messages::TangoConnect::Request &request, tango_ros_messages::TangoConnect::Response &response)
TangoErrorType TangoSetupConfig ()
void UpdateAndPublishTangoStatus (const TangoStatus &status)

Private Attributes

std::string area_description_frame_id_
geometry_msgs::TransformStamped area_description_T_start_of_service_
ros::Publisher area_description_T_start_of_service_publisher_
tf::StampedTransform camera_depth_T_laser_
sensor_msgs::CameraInfo color_camera_info_
std::shared_ptr
< camera_info_manager::CameraInfoManager
color_camera_info_manager_
image_geometry::PinholeCameraModel color_camera_model_
image_transport::CameraPublisher color_camera_publisher_
cv::Mat color_image_
std_msgs::Header color_image_header_
cv::Mat color_image_rect_
PublishThread color_image_thread_
image_transport::Publisher color_rectified_image_publisher_
cv::Mat cv_warp_map_x_
cv::Mat cv_warp_map_y_
PublishThread device_pose_thread_
geometry_msgs::TransformStamped device_T_camera_color_
geometry_msgs::TransformStamped device_T_camera_depth_
geometry_msgs::TransformStamped device_T_camera_fisheye_
bool enable_3dr_mesh_ = true
bool enable_3dr_occupancy_grid_ = true
bool enable_color_camera_ = true
bool enable_depth_ = true
bool fisheye_camera_available_ = true
sensor_msgs::CameraInfo fisheye_camera_info_
std::shared_ptr
< camera_info_manager::CameraInfoManager
fisheye_camera_info_manager_
image_transport::CameraPublisher fisheye_camera_publisher_
cv::Mat fisheye_image_
std_msgs::Header fisheye_image_header_
cv::Mat fisheye_image_rect_
PublishThread fisheye_image_thread_
image_transport::Publisher fisheye_rectified_image_publisher_
ros::ServiceServer get_map_name_service_
ros::ServiceServer get_map_uuids_service_
TangoSupport_ImageBufferManager * image_buffer_manager_
std::shared_ptr
< image_transport::ImageTransport
image_transport_
sensor_msgs::LaserScan laser_scan_
double laser_scan_max_height_ = 1.0
double laser_scan_max_range_ = 4.0
double laser_scan_min_height_ = -1.0
double laser_scan_min_range_ = 0.3
ros::Publisher laser_scan_publisher_
PublishThread laser_scan_thread_
Tango3DR_Pose last_camera_color_pose_
Tango3DR_Pose last_camera_depth_pose_
ros::ServiceServer load_occupancy_grid_service_
ros::Publisher mesh_marker_publisher_
PublishThread mesh_thread_
std::atomic_bool new_point_cloud_available_for_t3dr_
ros::NodeHandle node_handle_
nav_msgs::OccupancyGrid occupancy_grid_
ros::Publisher occupancy_grid_publisher_
sensor_msgs::PointCloud2 point_cloud_
TangoSupport_PointCloudManager * point_cloud_manager_
ros::Publisher point_cloud_publisher_
PublishThread point_cloud_thread_
bool publish_pose_on_tf_ = true
std::thread ros_spin_thread_
std::atomic_bool run_threads_
ros::ServiceServer save_map_service_
std::string start_of_service_frame_id_
geometry_msgs::TransformStamped start_of_service_T_device_
ros::Publisher start_of_service_T_device_publisher_
ros::Publisher static_occupancy_grid_publisher_
Tango3DR_CameraCalibration t3dr_color_camera_intrinsics_
Tango3DR_ReconstructionContext t3dr_context_
uint8_t t3dr_occupancy_grid_threshold_
double t3dr_resolution_
TangoConfig tango_config_
ros::ServiceServer tango_connect_service_
bool tango_data_available_ = true
TangoStatus tango_status_
ros::Publisher tango_status_publisher_
tf::TransformBroadcaster tf_broadcaster_
tf2_ros::StaticTransformBroadcaster tf_static_broadcaster_
double time_offset_ = 0.
bool use_tf_static_ = true

Detailed Description

Definition at line 128 of file tango_ros_nodelet.h.


Constructor & Destructor Documentation

Definition at line 258 of file tango_ros_nodelet.cpp.

Definition at line 364 of file tango_ros_nodelet.cpp.


Member Function Documentation

Definition at line 659 of file tango_ros_nodelet.cpp.

void tango_ros_native::TangoRosNodelet::DynamicReconfigureCallback ( PublisherConfig &  config,
uint32_t  level 
) [private]

Definition at line 1169 of file tango_ros_nodelet.cpp.

bool tango_ros_native::TangoRosNodelet::GetAvailableMapUuidsList ( std::vector< std::string > &  uuid_list)

Definition at line 1364 of file tango_ros_nodelet.cpp.

bool tango_ros_native::TangoRosNodelet::GetMapNameFromUuid ( const std::string &  map_uuid,
std::string &  map_name 
)

Definition at line 1380 of file tango_ros_nodelet.cpp.

bool tango_ros_native::TangoRosNodelet::GetMapNameServiceCallback ( const tango_ros_messages::GetMapName::Request &  req,
tango_ros_messages::GetMapName::Response &  res 
) [private]

Definition at line 1227 of file tango_ros_nodelet.cpp.

bool tango_ros_native::TangoRosNodelet::GetMapUuidsServiceCallback ( const tango_ros_messages::GetMapUuids::Request &  req,
tango_ros_messages::GetMapUuids::Response &  res 
) [private]

Definition at line 1233 of file tango_ros_nodelet.cpp.

bool tango_ros_native::TangoRosNodelet::LoadOccupancyGridServiceCallback ( const tango_ros_messages::LoadOccupancyGrid::Request &  req,
tango_ros_messages::LoadOccupancyGrid::Response &  res 
) [private]

Definition at line 1307 of file tango_ros_nodelet.cpp.

Definition at line 865 of file tango_ros_nodelet.cpp.

Implements nodelet::Nodelet.

Definition at line 262 of file tango_ros_nodelet.cpp.

Definition at line 813 of file tango_ros_nodelet.cpp.

Definition at line 788 of file tango_ros_nodelet.cpp.

Definition at line 368 of file tango_ros_nodelet.cpp.

Definition at line 1084 of file tango_ros_nodelet.cpp.

Definition at line 987 of file tango_ros_nodelet.cpp.

Definition at line 1047 of file tango_ros_nodelet.cpp.

Definition at line 1032 of file tango_ros_nodelet.cpp.

Definition at line 1120 of file tango_ros_nodelet.cpp.

Definition at line 1017 of file tango_ros_nodelet.cpp.

Definition at line 722 of file tango_ros_nodelet.cpp.

Definition at line 1180 of file tango_ros_nodelet.cpp.

bool tango_ros_native::TangoRosNodelet::SaveMapServiceCallback ( const tango_ros_messages::SaveMap::Request &  req,
tango_ros_messages::SaveMap::Response &  res 
) [private]

Definition at line 1248 of file tango_ros_nodelet.cpp.

Definition at line 922 of file tango_ros_nodelet.cpp.

Definition at line 939 of file tango_ros_nodelet.cpp.

Definition at line 598 of file tango_ros_nodelet.cpp.

bool tango_ros_native::TangoRosNodelet::TangoConnectServiceCallback ( const tango_ros_messages::TangoConnect::Request &  request,
tango_ros_messages::TangoConnect::Response &  response 
) [private]

Definition at line 1194 of file tango_ros_nodelet.cpp.

Definition at line 699 of file tango_ros_nodelet.cpp.

Definition at line 479 of file tango_ros_nodelet.cpp.

Definition at line 652 of file tango_ros_nodelet.cpp.


Member Data Documentation

Definition at line 237 of file tango_ros_nodelet.h.

Definition at line 243 of file tango_ros_nodelet.h.

Definition at line 241 of file tango_ros_nodelet.h.

Definition at line 246 of file tango_ros_nodelet.h.

sensor_msgs::CameraInfo tango_ros_native::TangoRosNodelet::color_camera_info_ [private]

Definition at line 273 of file tango_ros_nodelet.h.

Definition at line 274 of file tango_ros_nodelet.h.

Definition at line 277 of file tango_ros_nodelet.h.

Definition at line 271 of file tango_ros_nodelet.h.

Definition at line 276 of file tango_ros_nodelet.h.

Definition at line 272 of file tango_ros_nodelet.h.

Definition at line 278 of file tango_ros_nodelet.h.

Definition at line 218 of file tango_ros_nodelet.h.

Definition at line 275 of file tango_ros_nodelet.h.

Definition at line 267 of file tango_ros_nodelet.h.

Definition at line 268 of file tango_ros_nodelet.h.

Definition at line 214 of file tango_ros_nodelet.h.

geometry_msgs::TransformStamped tango_ros_native::TangoRosNodelet::device_T_camera_color_ [private]

Definition at line 248 of file tango_ros_nodelet.h.

geometry_msgs::TransformStamped tango_ros_native::TangoRosNodelet::device_T_camera_depth_ [private]

Definition at line 245 of file tango_ros_nodelet.h.

geometry_msgs::TransformStamped tango_ros_native::TangoRosNodelet::device_T_camera_fisheye_ [private]

Definition at line 247 of file tango_ros_nodelet.h.

Definition at line 233 of file tango_ros_nodelet.h.

Definition at line 234 of file tango_ros_nodelet.h.

Definition at line 232 of file tango_ros_nodelet.h.

Definition at line 231 of file tango_ros_nodelet.h.

Definition at line 235 of file tango_ros_nodelet.h.

Definition at line 263 of file tango_ros_nodelet.h.

Definition at line 264 of file tango_ros_nodelet.h.

Definition at line 261 of file tango_ros_nodelet.h.

Definition at line 266 of file tango_ros_nodelet.h.

Definition at line 262 of file tango_ros_nodelet.h.

Definition at line 269 of file tango_ros_nodelet.h.

Definition at line 217 of file tango_ros_nodelet.h.

Definition at line 265 of file tango_ros_nodelet.h.

Definition at line 296 of file tango_ros_nodelet.h.

Definition at line 297 of file tango_ros_nodelet.h.

TangoSupport_ImageBufferManager* tango_ros_native::TangoRosNodelet::image_buffer_manager_ [private]

Definition at line 288 of file tango_ros_nodelet.h.

Definition at line 260 of file tango_ros_nodelet.h.

sensor_msgs::LaserScan tango_ros_native::TangoRosNodelet::laser_scan_ [private]

Definition at line 254 of file tango_ros_nodelet.h.

Definition at line 255 of file tango_ros_nodelet.h.

Definition at line 257 of file tango_ros_nodelet.h.

Definition at line 256 of file tango_ros_nodelet.h.

Definition at line 258 of file tango_ros_nodelet.h.

Definition at line 253 of file tango_ros_nodelet.h.

Definition at line 216 of file tango_ros_nodelet.h.

Definition at line 289 of file tango_ros_nodelet.h.

Definition at line 287 of file tango_ros_nodelet.h.

Definition at line 299 of file tango_ros_nodelet.h.

Definition at line 280 of file tango_ros_nodelet.h.

Definition at line 219 of file tango_ros_nodelet.h.

Definition at line 222 of file tango_ros_nodelet.h.

Definition at line 212 of file tango_ros_nodelet.h.

nav_msgs::OccupancyGrid tango_ros_native::TangoRosNodelet::occupancy_grid_ [private]

Definition at line 282 of file tango_ros_nodelet.h.

Definition at line 281 of file tango_ros_nodelet.h.

sensor_msgs::PointCloud2 tango_ros_native::TangoRosNodelet::point_cloud_ [private]

Definition at line 251 of file tango_ros_nodelet.h.

TangoSupport_PointCloudManager* tango_ros_native::TangoRosNodelet::point_cloud_manager_ [private]

Definition at line 286 of file tango_ros_nodelet.h.

Definition at line 250 of file tango_ros_nodelet.h.

Definition at line 215 of file tango_ros_nodelet.h.

Definition at line 229 of file tango_ros_nodelet.h.

Definition at line 220 of file tango_ros_nodelet.h.

Definition at line 221 of file tango_ros_nodelet.h.

Definition at line 298 of file tango_ros_nodelet.h.

Definition at line 236 of file tango_ros_nodelet.h.

geometry_msgs::TransformStamped tango_ros_native::TangoRosNodelet::start_of_service_T_device_ [private]

Definition at line 242 of file tango_ros_nodelet.h.

Definition at line 240 of file tango_ros_nodelet.h.

Definition at line 294 of file tango_ros_nodelet.h.

Definition at line 290 of file tango_ros_nodelet.h.

Definition at line 285 of file tango_ros_nodelet.h.

Definition at line 292 of file tango_ros_nodelet.h.

Definition at line 291 of file tango_ros_nodelet.h.

Definition at line 211 of file tango_ros_nodelet.h.

Definition at line 300 of file tango_ros_nodelet.h.

Definition at line 227 of file tango_ros_nodelet.h.

Definition at line 225 of file tango_ros_nodelet.h.

Definition at line 224 of file tango_ros_nodelet.h.

Definition at line 239 of file tango_ros_nodelet.h.

Definition at line 244 of file tango_ros_nodelet.h.

Definition at line 228 of file tango_ros_nodelet.h.

Definition at line 230 of file tango_ros_nodelet.h.


The documentation for this class was generated from the following files:


tango_ros_native
Author(s):
autogenerated on Thu Jun 6 2019 19:49:54