#include <gazebo_ros_image_sonar.hh>
|
virtual void | OnNewDepthFrame (const float *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format) |
| Update the controller. More...
|
|
virtual void | OnNewImageFrame (const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format) |
| Update the controller. More...
|
|
virtual void | OnNewRGBPointCloud (const float *_pcd, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format) |
| Update the controller. More...
|
|
virtual void | PublishCameraInfo () |
|
|
void | ApplyMedianFilter (cv::Mat &scan) |
|
void | ApplySmoothing (cv::Mat &scan, float fov) |
|
void | ApplySpeckleNoise (cv::Mat &scan, float fov) |
|
cv::Mat | ComputeNormalImage (cv::Mat &depth) |
|
void | ComputeSonarImage (const float *_src) |
| push depth image data into ros topic More...
|
|
cv::Mat | ConstructScanImage (cv::Mat &depth, cv::Mat &SNR) |
|
cv::Mat | ConstructSonarImage (cv::Mat &depth, cv::Mat &normals) |
|
cv::Mat | ConstructVisualScanImage (cv::Mat &raw_scan) |
|
void | DepthImageConnect () |
|
void | DepthImageDisconnect () |
|
void | DepthInfoConnect () |
|
void | DepthInfoDisconnect () |
|
void | FillDepthImage (const float *_src) |
| push depth image data into ros topic More...
|
|
bool | FillDepthImageHelper (sensor_msgs::Image &image_msg, uint32_t rows_arg, uint32_t cols_arg, uint32_t step_arg, void *data_arg) |
|
bool | FillPointCloudHelper (sensor_msgs::PointCloud2 &point_cloud_msg, uint32_t rows_arg, uint32_t cols_arg, uint32_t step_arg, void *data_arg) |
|
void | FillPointdCloud (const float *_src) |
| Put camera data to the ROS topic. More...
|
|
void | InfoConnect () |
|
void | InfoDisconnect () |
|
void | MultibeamImageConnect () |
|
void | MultibeamImageDisconnect () |
|
void | NormalImageConnect () |
|
void | NormalImageDisconnect () |
|
void | PointCloudConnect () |
|
void | PointCloudDisconnect () |
|
void | RawSonarImageConnect () |
|
void | RawSonarImageDisconnect () |
|
void | SonarImageConnect () |
|
void | SonarImageDisconnect () |
|
| GazeboRosCameraUtils () |
|
void | Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf, const std::string &_camera_name_suffix="") |
|
void | Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf, const std::string &_camera_name_suffix, double _hack_baseline) |
|
event::ConnectionPtr | OnLoad (const boost::function< void()> &) |
|
| ~GazeboRosCameraUtils () |
|
void | CameraQueueThread () |
|
virtual bool | CanTriggerCamera () |
|
void | ImageConnect () |
|
void | ImageDisconnect () |
|
void | PublishCameraInfo () |
|
void | PublishCameraInfo (ros::Publisher camera_info_publisher) |
|
void | PublishCameraInfo (common::Time &last_update_time) |
|
void | PutCameraData (const unsigned char *_src) |
|
void | PutCameraData (const unsigned char *_src, common::Time &last_update_time) |
|
virtual void | TriggerCamera () |
|
Definition at line 73 of file gazebo_ros_image_sonar.hh.
gazebo::GazeboRosImageSonar::GazeboRosImageSonar |
( |
| ) |
|
gazebo::GazeboRosImageSonar::~GazeboRosImageSonar |
( |
| ) |
|
void gazebo::GazeboRosImageSonar::Advertise |
( |
| ) |
|
|
virtual |
void gazebo::GazeboRosImageSonar::ApplyMedianFilter |
( |
cv::Mat & |
scan | ) |
|
|
private |
void gazebo::GazeboRosImageSonar::ApplySmoothing |
( |
cv::Mat & |
scan, |
|
|
float |
fov |
|
) |
| |
|
private |
void gazebo::GazeboRosImageSonar::ApplySpeckleNoise |
( |
cv::Mat & |
scan, |
|
|
float |
fov |
|
) |
| |
|
private |
cv::Mat gazebo::GazeboRosImageSonar::ComputeNormalImage |
( |
cv::Mat & |
depth | ) |
|
|
private |
void gazebo::GazeboRosImageSonar::ComputeSonarImage |
( |
const float * |
_src | ) |
|
|
private |
cv::Mat gazebo::GazeboRosImageSonar::ConstructScanImage |
( |
cv::Mat & |
depth, |
|
|
cv::Mat & |
SNR |
|
) |
| |
|
private |
cv::Mat gazebo::GazeboRosImageSonar::ConstructSonarImage |
( |
cv::Mat & |
depth, |
|
|
cv::Mat & |
normals |
|
) |
| |
|
private |
cv::Mat gazebo::GazeboRosImageSonar::ConstructVisualScanImage |
( |
cv::Mat & |
raw_scan | ) |
|
|
private |
void gazebo::GazeboRosImageSonar::DepthImageConnect |
( |
| ) |
|
|
private |
void gazebo::GazeboRosImageSonar::DepthImageDisconnect |
( |
| ) |
|
|
private |
void gazebo::GazeboRosImageSonar::DepthInfoConnect |
( |
| ) |
|
|
private |
void gazebo::GazeboRosImageSonar::DepthInfoDisconnect |
( |
| ) |
|
|
private |
void gazebo::GazeboRosImageSonar::FillDepthImage |
( |
const float * |
_src | ) |
|
|
private |
bool gazebo::GazeboRosImageSonar::FillDepthImageHelper |
( |
sensor_msgs::Image & |
image_msg, |
|
|
uint32_t |
rows_arg, |
|
|
uint32_t |
cols_arg, |
|
|
uint32_t |
step_arg, |
|
|
void * |
data_arg |
|
) |
| |
|
private |
bool gazebo::GazeboRosImageSonar::FillPointCloudHelper |
( |
sensor_msgs::PointCloud2 & |
point_cloud_msg, |
|
|
uint32_t |
rows_arg, |
|
|
uint32_t |
cols_arg, |
|
|
uint32_t |
step_arg, |
|
|
void * |
data_arg |
|
) |
| |
|
private |
void gazebo::GazeboRosImageSonar::FillPointdCloud |
( |
const float * |
_src | ) |
|
|
private |
void gazebo::GazeboRosImageSonar::InfoConnect |
( |
| ) |
|
|
private |
void gazebo::GazeboRosImageSonar::InfoDisconnect |
( |
| ) |
|
|
private |
void gazebo::GazeboRosImageSonar::Load |
( |
sensors::SensorPtr |
_parent, |
|
|
sdf::ElementPtr |
_sdf |
|
) |
| |
|
virtual |
void gazebo::GazeboRosImageSonar::MultibeamImageConnect |
( |
| ) |
|
|
private |
void gazebo::GazeboRosImageSonar::MultibeamImageDisconnect |
( |
| ) |
|
|
private |
void gazebo::GazeboRosImageSonar::NormalImageConnect |
( |
| ) |
|
|
private |
void gazebo::GazeboRosImageSonar::NormalImageDisconnect |
( |
| ) |
|
|
private |
void gazebo::GazeboRosImageSonar::OnNewDepthFrame |
( |
const float * |
_image, |
|
|
unsigned int |
_width, |
|
|
unsigned int |
_height, |
|
|
unsigned int |
_depth, |
|
|
const std::string & |
_format |
|
) |
| |
|
protectedvirtual |
void gazebo::GazeboRosImageSonar::OnNewImageFrame |
( |
const unsigned char * |
_image, |
|
|
unsigned int |
_width, |
|
|
unsigned int |
_height, |
|
|
unsigned int |
_depth, |
|
|
const std::string & |
_format |
|
) |
| |
|
protectedvirtual |
void gazebo::GazeboRosImageSonar::OnNewRGBPointCloud |
( |
const float * |
_pcd, |
|
|
unsigned int |
_width, |
|
|
unsigned int |
_height, |
|
|
unsigned int |
_depth, |
|
|
const std::string & |
_format |
|
) |
| |
|
protectedvirtual |
void gazebo::GazeboRosImageSonar::PointCloudConnect |
( |
| ) |
|
|
private |
void gazebo::GazeboRosImageSonar::PointCloudDisconnect |
( |
| ) |
|
|
private |
void gazebo::GazeboRosImageSonar::PublishCameraInfo |
( |
| ) |
|
|
protectedvirtual |
void gazebo::GazeboRosImageSonar::RawSonarImageConnect |
( |
| ) |
|
|
private |
void gazebo::GazeboRosImageSonar::RawSonarImageDisconnect |
( |
| ) |
|
|
private |
void gazebo::GazeboRosImageSonar::SonarImageConnect |
( |
| ) |
|
|
private |
void gazebo::GazeboRosImageSonar::SonarImageDisconnect |
( |
| ) |
|
|
private |
std::vector<int> gazebo::GazeboRosImageSonar::angle_nbr_indices_ |
|
protected |
std::vector<std::vector<int> > gazebo::GazeboRosImageSonar::angle_range_indices_ |
|
protected |
unsigned int gazebo::GazeboRosImageSonar::depth |
|
protected |
ros::Publisher gazebo::GazeboRosImageSonar::depth_image_camera_info_pub_ |
|
protected |
std::string gazebo::GazeboRosImageSonar::depth_image_camera_info_topic_name_ |
|
private |
int gazebo::GazeboRosImageSonar::depth_image_connect_count_ |
|
private |
sensor_msgs::Image gazebo::GazeboRosImageSonar::depth_image_msg_ |
|
private |
std::string gazebo::GazeboRosImageSonar::depth_image_topic_name_ |
|
private |
int gazebo::GazeboRosImageSonar::depth_info_connect_count_ |
|
private |
common::Time gazebo::GazeboRosImageSonar::depth_sensor_update_time_ |
|
private |
rendering::DepthCameraPtr gazebo::GazeboRosImageSonar::depthCamera |
|
protected |
cv::Mat gazebo::GazeboRosImageSonar::dist_matrix_ |
|
protected |
std::string gazebo::GazeboRosImageSonar::format |
|
protected |
std::default_random_engine gazebo::GazeboRosImageSonar::generator |
|
private |
unsigned int gazebo::GazeboRosImageSonar::height |
|
protected |
common::Time gazebo::GazeboRosImageSonar::last_depth_image_camera_info_update_time_ |
|
private |
sensor_msgs::Image gazebo::GazeboRosImageSonar::multibeam_image_msg_ |
|
private |
sensor_msgs::Image gazebo::GazeboRosImageSonar::normal_image_msg_ |
|
private |
sensors::DepthCameraSensorPtr gazebo::GazeboRosImageSonar::parentSensor |
|
protected |
int gazebo::GazeboRosImageSonar::point_cloud_connect_count_ |
|
private |
double gazebo::GazeboRosImageSonar::point_cloud_cutoff_ |
|
private |
sensor_msgs::PointCloud2 gazebo::GazeboRosImageSonar::point_cloud_msg_ |
|
private |
std::string gazebo::GazeboRosImageSonar::point_cloud_topic_name_ |
|
private |
sensor_msgs::Image gazebo::GazeboRosImageSonar::raw_sonar_image_msg_ |
|
private |
sensor_msgs::Image gazebo::GazeboRosImageSonar::sonar_image_msg_ |
|
private |
unsigned int gazebo::GazeboRosImageSonar::width |
|
protected |
The documentation for this class was generated from the following files: