Corentin Chauvin-Hameau – 2019-2020
Coverage Path Planning for an underwater robot surveying a marine farm
Classes | Public Member Functions | Private Member Functions | Static Private Member Functions | Private Attributes | Static Private Attributes | List of all members
mfcpp::CameraNodelet Class Reference

Nodelet for a simulated camera. More...

#include <camera_nodelet.hpp>

Inheritance diagram for mfcpp::CameraNodelet:
Inheritance graph
[legend]
Collaboration diagram for mfcpp::CameraNodelet:
Collaboration graph
[legend]

Classes

class  OverlapCallback
 Callback class for overlap detection. More...
 
class  RaycastCallback
 Callback class for raycasting. More...
 

Public Member Functions

 CameraNodelet ()
 
 ~CameraNodelet ()
 
virtual void onInit ()
 Function called at beginning of nodelet execution. More...
 

Private Member Functions

void main_cb (const ros::TimerEvent &timer_event)
 Main callback which is called by a timer. More...
 
void algae_cb (const mf_farm_simulator::AlgaeConstPtr msg)
 Callback for the algae of the farm. More...
 
void init_coll_world ()
 Initialise the collision world. More...
 
void update_algae ()
 Updates algae in the collision world. More...
 
bool get_tf ()
 Gets tf transforms. More...
 
bool multi_fov_body (const std::vector< geometry_msgs::Pose > &poses, rp3d::CollisionBody *body, std::unique_ptr< rp3d::BoxShape > &shape, ros::Time stamp=ros::Time(0))
 Fill a collision body for multi-pose FOV overlap. More...
 
bool ray_multi_cb (mf_sensors_simulator::MultiPoses::Request &req, mf_sensors_simulator::MultiPoses::Response &res)
 Service callback for raycasting from several camera poses. More...
 
void publish_rviz_fov ()
 Publishes a Rviz marker for the camera field of view. More...
 
void update_fov_pose ()
 Updates pose of field of view body. More...
 
void overlap_fov (rp3d::CollisionBody *body)
 Selects algae that are in field of view of the camera. More...
 
void get_ray_algae_carac (std::vector< float > &w_algae, std::vector< float > &h_algae, std::vector< float > &inc_y3, std::vector< float > &inc_z3, std::vector< geometry_msgs::TransformStamped > &tf_algae)
 Gets position, dimension and axes of the algae for raycasting. More...
 
tf2::Vector3 get_aim_pt (int pxl_h, int pxl_w, int n_pixel_h=-1, int n_pixel_w=-1)
 Gets an aim point from pixel coordinates for raycasting. More...
 
rp3d::Vector3 tf2_to_rp3d (const tf2::Vector3 vect)
 Converts a tf2 vector to a rp3d vector. More...
 
geometry_msgs::TransformStamped pose_to_tf (const geometry_msgs::Pose &pose)
 Converts a pose to a transform. More...
 
geometry_msgs::TransformStamped inverse_tf (const geometry_msgs::TransformStamped &transform)
 Inverse a transform. More...
 
geometry_msgs::TransformStamped combine_transforms (const std::vector< geometry_msgs::TransformStamped > &transforms)
 Combine transforms sequentially. More...
 
tf2::Vector3 apply_transform (const tf2::Vector3 &in_vector, const geometry_msgs::TransformStamped &transform)
 Applies a transform to a vector. More...
 
bool raycast_alga (const tf2::Vector3 &aim_pt, tf2::Vector3 &hit_pt, int &alga_idx, const geometry_msgs::TransformStamped &fixed_camera_tf, const tf2::Vector3 &origin=tf2::Vector3(0, 0, 0))
 Casts a ray on algae and gets hit point. More...
 
bool raycast_alga (const tf2::Vector3 &aim_pt, float &distance, const geometry_msgs::TransformStamped &fixed_camera_tf, const tf2::Vector3 &origin=tf2::Vector3(0, 0, 0))
 Casts a ray on algae and gets hit distance. More...
 
bool raycast_wall (const geometry_msgs::Pose &vp_pose, int n_pxl_h, int n_pxl_w, mf_sensors_simulator::CameraOutput &pxl_output, ros::Time stamp=ros::Time(0))
 
void interpolate_quadri (const tf2::Vector3 &p1, const tf2::Vector3 &p2, const tf2::Vector3 &p3, const tf2::Vector3 &p4, int n_h, int n_w, std::vector< float > &x_list, std::vector< float > &y_list, std::vector< float > &z_list)
 Interpolates a 3D quadrilateral lying on a plane. More...
 
void prepare_out_msgs (mf_sensors_simulator::CameraOutput &out_msg, visualization_msgs::Marker &ray_marker, visualization_msgs::Marker &pts_marker)
 Prepares the ROS output messages. More...
 
void add_pt_to_marker (visualization_msgs::Marker &marker, const tf2::Vector3 &pt, float color_r, float color_g, float color_b)
 Add a point to a point marker. More...
 
void add_line_to_marker (visualization_msgs::Marker &marker, const tf2::Vector3 &pt1, const tf2::Vector3 &pt2)
 Add a point to a point marker. More...
 
void publish_output ()
 Publishes camera output. More...
 

Static Private Member Functions

static void sigint_handler (int s)
 SINGINT (Ctrl+C) callback to stop the nodelet properly. More...
 

Private Attributes

ros::NodeHandle nh_
 Node handler (for topics and services) More...
 
ros::NodeHandle private_nh_
 Private node handler (for parameters) More...
 
ros::Subscriber algae_sub_
 Subscriber for the algae of the farm. More...
 
ros::ServiceServer ray_multi_serv_
 Service for raycasting from several camera poses. More...
 
ros::Publisher out_pub_
 Publisher for the camera output. More...
 
ros::Publisher rviz_pub_
 Publisher for Rviz markers. More...
 
tf2_ros::Buffer tf_buffer_
 
tf2_ros::TransformListener tf_listener_
 
mf_farm_simulator::AlgaeConstPtr last_algae_msg_
 Last algae message. More...
 
bool algae_msg_received_
 Whether an algae message has been received. More...
 
geometry_msgs::TransformStamped fixed_camera_tf_
 Transform from fixed frame to camera. More...
 
geometry_msgs::TransformStamped camera_fixed_tf_
 Transform from camera to fixed frame. More...
 
geometry_msgs::TransformStamped camera_robot_tf_
 Transform from camera to robot frame. More...
 
geometry_msgs::TransformStamped robot_camera_tf_
 Transform from robot to camera frame. More...
 
std::vector< std::vector< std::vector< float > > > heatmaps_
 Disease heatmatps for all the algae. More...
 
std::vector< int > corr_algae_
 Correspondance between the algae used for raytracing and all the others. More...
 
std::mutex coll_mutex_
 Mutex to control access to collision variables. More...
 
Collision members
bool world_init_
 Whether the collision world has been initialised. More...
 
rp3d::CollisionWorld coll_world_
 World with all algae and camera FOV. More...
 
rp3d::CollisionWorld ray_world_
 World with algae colliding with FOV. More...
 
rp3d::WorldSettings world_settings_
 Collision world settings. More...
 
std::vector< rp3d::CollisionBody * > algae_bodies_
 Collision bodies of the algae. More...
 
std::vector< rp3d::CollisionBody * > ray_bodies_
 Collision bodies for raycasting. More...
 
rp3d::CollisionBody * fov_body_
 Collision body of the camera FOV. More...
 
std::vector< box_shape_ptralgae_shapes_
 Collision shapes of the algae bodies. More...
 
std::vector< box_shape_ptrray_shapes_
 Collision shapes of algae for raycasting. More...
 
box_shape_ptr fov_shape_
 Collision shapes of the FOV body. More...
 
RaycastCallback raycast_cb_
 Callback instance for raycasting. More...
 
OverlapCallback overlap_cb_
 
ROS parameters
float camera_freq_
 Frequency of the sensor. More...
 
std::string fixed_frame_
 Frame in which the pose is expressed. More...
 
std::string robot_frame_
 Frame of the robot. More...
 
std::string camera_frame_
 Frame of the camera. More...
 
std::vector< float > fov_color_
 Color of the camera field of view Rviz marker. More...
 
float focal_length_
 Focal length of the camera. More...
 
float sensor_width_
 Width of the camera sensor. More...
 
float sensor_height_
 Height of the camera sensor. More...
 
float fov_distance_
 Maximum distance detected by the camera. More...
 
int n_pxl_height_
 Nbr of pixels along sensor height. More...
 
int n_pxl_width_
 Nbr of pixels along sensor width. More...
 
bool noise_meas_
 Whether to noise measurements on disease heatmap. More...
 
float noise_std_
 Maximum standard deviation of the measurement noise. More...
 
float noise_decay_
 

Static Private Attributes

static sig_atomic_t volatile b_sigint_ = 0
 Whether SIGINT signal has been received. More...
 
static ros::Timer main_timer_ = ros::Timer()
 Timer callback for the main function. More...
 

Detailed Description

Nodelet for a simulated camera.

For each pixel, the simulated sensor casts a ray. If the ray touches an alga, the sensor will return the hit position, and the corresponding value of the alga disease heatmap.

To improve performance, two collision worlds are created:

A first step is then to test overlap between the camera FOV and the algae, the overlapping algae populates the small collision world. Therefore, raycasting is performed on a smaller amount of algae.

Definition at line 50 of file camera_nodelet.hpp.

Constructor & Destructor Documentation

mfcpp::CameraNodelet::CameraNodelet ( )

Definition at line 45 of file camera_nodelet.cpp.

mfcpp::CameraNodelet::~CameraNodelet ( )

Definition at line 53 of file camera_nodelet.cpp.

Member Function Documentation

void mfcpp::CameraNodelet::add_line_to_marker ( visualization_msgs::Marker &  marker,
const tf2::Vector3 &  pt1,
const tf2::Vector3 &  pt2 
)
private

Add a point to a point marker.

Parameters
[out]markerMarker to fill
[in]pt1First point to add to the marker
[in]pt2Second point to add to the marker

Definition at line 150 of file output.cpp.

void mfcpp::CameraNodelet::add_pt_to_marker ( visualization_msgs::Marker &  marker,
const tf2::Vector3 &  pt,
float  color_r,
float  color_g,
float  color_b 
)
private

Add a point to a point marker.

Parameters
[out]markerMarker to fill
[in]ptPoint to add to the marker
[in]color_rRed channel of the point color
[in]color_gGreen channel of the point color
[in]color_bBlue channel of the point color

Definition at line 132 of file output.cpp.

void mfcpp::CameraNodelet::algae_cb ( const mf_farm_simulator::AlgaeConstPtr  msg)
private

Callback for the algae of the farm.

Parameters
msgPointer to the algae

Definition at line 140 of file camera_nodelet.cpp.

tf2::Vector3 mfcpp::CameraNodelet::apply_transform ( const tf2::Vector3 &  in_vector,
const geometry_msgs::TransformStamped &  transform 
)
private

Applies a transform to a vector.

Parameters
[in]in_vectorVector to transform
[in]transformTransform to apply return Transformed vector

Definition at line 257 of file collision.cpp.

geometry_msgs::TransformStamped mfcpp::CameraNodelet::combine_transforms ( const std::vector< geometry_msgs::TransformStamped > &  transforms)
private

Combine transforms sequentially.

Parameters
transformsList of transform to combine
Returns
Product of all transforms

Definition at line 223 of file collision.cpp.

tf2::Vector3 mfcpp::CameraNodelet::get_aim_pt ( int  pxl_h,
int  pxl_w,
int  n_pixel_h = -1,
int  n_pixel_w = -1 
)
private

Gets an aim point from pixel coordinates for raycasting.

The raycast will be performed between the camera origin and this aim point. The norm of the aim point is the field of view distance.

Parameters
pxl_hPixel coordinate in height axis
pxl_wPixel coordinate in width axis
n_pxl_hCustom total number of pixels of the camera in height (defaulted to global value)
n_pxl_wCustom total number of pixels of the camera in width (defaulted to global value)
Returns
The corresponding aim point

Definition at line 206 of file collision.cpp.

void mfcpp::CameraNodelet::get_ray_algae_carac ( std::vector< float > &  w_algae,
std::vector< float > &  h_algae,
std::vector< float > &  inc_y3,
std::vector< float > &  inc_z3,
std::vector< geometry_msgs::TransformStamped > &  tf_algae 
)
private

Gets position, dimension and axes of the algae for raycasting.

Parameters
[out]w_algaeWidth of the algae
[out]h_algaeHeight of the algae
[out]inc_y3Increment along y3 algae axis
[out]inc_z3Increment along z3 algae axis
[out]tf_algaeTransforms of algae local frames

Definition at line 174 of file collision.cpp.

bool mfcpp::CameraNodelet::get_tf ( )
private

Gets tf transforms.

Returns
Whether a transform has been received

Definition at line 221 of file camera_nodelet.cpp.

void mfcpp::CameraNodelet::init_coll_world ( )
private

Initialise the collision world.

Definition at line 147 of file camera_nodelet.cpp.

void mfcpp::CameraNodelet::interpolate_quadri ( const tf2::Vector3 &  p1,
const tf2::Vector3 &  p2,
const tf2::Vector3 &  p3,
const tf2::Vector3 &  p4,
int  n_h,
int  n_w,
std::vector< float > &  x_list,
std::vector< float > &  y_list,
std::vector< float > &  z_list 
)
private

Interpolates a 3D quadrilateral lying on a plane.

It uses bilinear mapping to transform points in [-1, 1]x[-1, 1] to 3D points inside a quadrilateral defined by its four corners.

For $ (u, v) \in [-1, 1]^2 $, the mapping to corresponding $ (x, y, z) $ coordinates is as follow:

  • $ x(u, v) = \alpha_0 + \alpha_1 u + \alpha_2 v + \alpha_3 u v $
  • $ y(u, v) = \beta_0 + \beta_1 u + \beta_2 v + \beta_3 u v $
  • $ z(u, v) = \gamma_0 + \gamma_1 u + \gamma_2 v + \gamma_3 u v $

Where $ \alpha $, $ \beta $ and $ \gamma $ are determined thanks to the corner points. For more information, you can refer to: The Finite Element Method: Linear Static and Dynamic Finite Element Analysis by Thomas J. R. Hughes (chapter 3.2).

Note
- The four corners are not added.
- Points will be emplaced back to the x, y, and z lists, so it assumes that their size is already reserved before.
Parameters
[in]p1Top left corner of the quadrilateral
[in]p2Bottom left corner of the quadrilateral
[in]p3Bottom right corner of the quadrilateral
[in]p4Top right corner of the quadrilateral
[in]n_hNumber of points to interpolate in the height direction
[in]n_wNumber of points to interpolate in the width direction
[out]x_listX coordinates of the interpolated points
[out]y_listY coordinates of the interpolated points
[out]z_listZ coordinates of the interpolated points

Definition at line 433 of file collision.cpp.

geometry_msgs::TransformStamped mfcpp::CameraNodelet::inverse_tf ( const geometry_msgs::TransformStamped &  transform)
inlineprivate

Inverse a transform.

Warning
Doesn't fill the header
Parameters
transformTransform to inverse
Returns
Inversed transform

Definition at line 485 of file camera_nodelet.hpp.

void mfcpp::CameraNodelet::main_cb ( const ros::TimerEvent &  timer_event)
private

Main callback which is called by a timer.

Parameters
timer_eventTimer event information

Definition at line 112 of file camera_nodelet.cpp.

bool mfcpp::CameraNodelet::multi_fov_body ( const std::vector< geometry_msgs::Pose > &  poses,
rp3d::CollisionBody *  body,
std::unique_ptr< rp3d::BoxShape > &  shape,
ros::Time  stamp = ros::Time(0) 
)
private

Fill a collision body for multi-pose FOV overlap.

The collision body is the smallest AABB containing each FOV of each pose. The corresponding collision shape is also filled.

Parameters
[in]posesVector of poses
[out]bodyBody to fill
[out]shapeCollision shape of the body
[in]stampTime at which to retrieve ROS transforms return Whether the call was successful

Definition at line 76 of file collision.cpp.

void mfcpp::CameraNodelet::onInit ( )
virtual

Function called at beginning of nodelet execution.

Definition at line 56 of file camera_nodelet.cpp.

void mfcpp::CameraNodelet::overlap_fov ( rp3d::CollisionBody *  body)
private

Selects algae that are in field of view of the camera.

The function will update CameraNodelet::corr_algae_, CameraNodelet::ray_world_, CameraNodelet::ray_bodies_ and CameraNodelet::ray_shapes_.

Parameters
bodyCollision body to check overlap with algae

Definition at line 160 of file collision.cpp.

geometry_msgs::TransformStamped mfcpp::CameraNodelet::pose_to_tf ( const geometry_msgs::Pose &  pose)
inlineprivate

Converts a pose to a transform.

Warning
This doesn't take into account frame ids and doesn't fill header
Parameters
posePose to convert
Returns
Converted transform

Definition at line 469 of file camera_nodelet.hpp.

void mfcpp::CameraNodelet::prepare_out_msgs ( mf_sensors_simulator::CameraOutput &  out_msg,
visualization_msgs::Marker &  ray_marker,
visualization_msgs::Marker &  pts_marker 
)
private

Prepares the ROS output messages.

Parameters
[out]out_msgsCamera output message
[out]ray_markerRviz marker for displaying the rays
[out]pts_markerRviz marker for displaying the hit points

Definition at line 85 of file output.cpp.

void mfcpp::CameraNodelet::publish_output ( )
private

Publishes camera output.

Definition at line 165 of file output.cpp.

void mfcpp::CameraNodelet::publish_rviz_fov ( )
private

Publishes a Rviz marker for the camera field of view.

Definition at line 24 of file output.cpp.

bool mfcpp::CameraNodelet::ray_multi_cb ( mf_sensors_simulator::MultiPoses::Request &  req,
mf_sensors_simulator::MultiPoses::Response &  res 
)
private

Service callback for raycasting from several camera poses.

This service raycast one line for each corner of the camera screen. It only returns the hit points position, not the algae disease values.

Definition at line 244 of file camera_nodelet.cpp.

bool mfcpp::CameraNodelet::raycast_alga ( const tf2::Vector3 &  aim_pt,
tf2::Vector3 &  hit_pt,
int &  alga_idx,
const geometry_msgs::TransformStamped &  fixed_camera_tf,
const tf2::Vector3 &  origin = tf2::Vector3(0, 0, 0) 
)
private

Casts a ray on algae and gets hit point.

Parameters
[in]aim_ptPoint towards which casting the ray (in camera frame)
[out]hit_ptHit point (in fixed frame)
[out]alga_idxIndex of the hit alga in the ray_bodies_ vector
[in]originOrigin of the ray (in camera frame)
[in]fixed_camera_tfTransform from fixed to camera frames
Returns
Whether an alga has been hit

Definition at line 271 of file collision.cpp.

bool mfcpp::CameraNodelet::raycast_alga ( const tf2::Vector3 &  aim_pt,
float &  distance,
const geometry_msgs::TransformStamped &  fixed_camera_tf,
const tf2::Vector3 &  origin = tf2::Vector3(0, 0, 0) 
)
private

Casts a ray on algae and gets hit distance.

Parameters
[in]aim_ptPoint towards which casting the ray (in camera frame)
[out]distanceDistance to the hit alga
[in]originOrigin of the ray (in camera frame)
[in]fixed_camera_tfTransform from fixed to camera frames
Returns
Whether an alga has been hit

Definition at line 300 of file collision.cpp.

bool mfcpp::CameraNodelet::raycast_wall ( const geometry_msgs::Pose &  vp_pose,
int  n_pxl_h,
int  n_pxl_w,
mf_sensors_simulator::CameraOutput &  pxl_output,
ros::Time  stamp = ros::Time(0) 
)
private

Definition at line 321 of file collision.cpp.

void mfcpp::CameraNodelet::sigint_handler ( int  s)
staticprivate

SINGINT (Ctrl+C) callback to stop the nodelet properly.

Definition at line 132 of file camera_nodelet.cpp.

rp3d::Vector3 mfcpp::CameraNodelet::tf2_to_rp3d ( const tf2::Vector3  vect)
inlineprivate

Converts a tf2 vector to a rp3d vector.

Parameters
vectVector to convert

Definition at line 463 of file camera_nodelet.hpp.

void mfcpp::CameraNodelet::update_algae ( )
private

Updates algae in the collision world.

Definition at line 203 of file camera_nodelet.cpp.

void mfcpp::CameraNodelet::update_fov_pose ( )
private

Updates pose of field of view body.

Definition at line 145 of file collision.cpp.

Member Data Documentation

std::vector<rp3d::CollisionBody*> mfcpp::CameraNodelet::algae_bodies_
private

Collision bodies of the algae.

Definition at line 123 of file camera_nodelet.hpp.

bool mfcpp::CameraNodelet::algae_msg_received_
private

Whether an algae message has been received.

Definition at line 108 of file camera_nodelet.hpp.

std::vector<box_shape_ptr> mfcpp::CameraNodelet::algae_shapes_
private

Collision shapes of the algae bodies.

Definition at line 126 of file camera_nodelet.hpp.

ros::Subscriber mfcpp::CameraNodelet::algae_sub_
private

Subscriber for the algae of the farm.

Definition at line 100 of file camera_nodelet.hpp.

sig_atomic_t volatile mfcpp::CameraNodelet::b_sigint_ = 0
staticprivate

Whether SIGINT signal has been received.

Definition at line 94 of file camera_nodelet.hpp.

geometry_msgs::TransformStamped mfcpp::CameraNodelet::camera_fixed_tf_
private

Transform from camera to fixed frame.

Definition at line 110 of file camera_nodelet.hpp.

std::string mfcpp::CameraNodelet::camera_frame_
private

Frame of the camera.

Definition at line 140 of file camera_nodelet.hpp.

float mfcpp::CameraNodelet::camera_freq_
private

Frequency of the sensor.

Definition at line 137 of file camera_nodelet.hpp.

geometry_msgs::TransformStamped mfcpp::CameraNodelet::camera_robot_tf_
private

Transform from camera to robot frame.

Definition at line 111 of file camera_nodelet.hpp.

std::mutex mfcpp::CameraNodelet::coll_mutex_
private

Mutex to control access to collision variables.

Definition at line 115 of file camera_nodelet.hpp.

rp3d::CollisionWorld mfcpp::CameraNodelet::coll_world_
private

World with all algae and camera FOV.

Definition at line 120 of file camera_nodelet.hpp.

std::vector<int> mfcpp::CameraNodelet::corr_algae_
private

Correspondance between the algae used for raytracing and all the others.

Definition at line 114 of file camera_nodelet.hpp.

geometry_msgs::TransformStamped mfcpp::CameraNodelet::fixed_camera_tf_
private

Transform from fixed frame to camera.

Definition at line 109 of file camera_nodelet.hpp.

std::string mfcpp::CameraNodelet::fixed_frame_
private

Frame in which the pose is expressed.

Definition at line 138 of file camera_nodelet.hpp.

float mfcpp::CameraNodelet::focal_length_
private

Focal length of the camera.

Definition at line 143 of file camera_nodelet.hpp.

rp3d::CollisionBody* mfcpp::CameraNodelet::fov_body_
private

Collision body of the camera FOV.

Definition at line 125 of file camera_nodelet.hpp.

std::vector<float> mfcpp::CameraNodelet::fov_color_
private

Color of the camera field of view Rviz marker.

Definition at line 141 of file camera_nodelet.hpp.

float mfcpp::CameraNodelet::fov_distance_
private

Maximum distance detected by the camera.

Definition at line 146 of file camera_nodelet.hpp.

box_shape_ptr mfcpp::CameraNodelet::fov_shape_
private

Collision shapes of the FOV body.

Definition at line 128 of file camera_nodelet.hpp.

std::vector<std::vector<std::vector<float> > > mfcpp::CameraNodelet::heatmaps_
private

Disease heatmatps for all the algae.

Definition at line 113 of file camera_nodelet.hpp.

mf_farm_simulator::AlgaeConstPtr mfcpp::CameraNodelet::last_algae_msg_
private

Last algae message.

Definition at line 107 of file camera_nodelet.hpp.

ros::Timer mfcpp::CameraNodelet::main_timer_ = ros::Timer()
staticprivate

Timer callback for the main function.

Definition at line 95 of file camera_nodelet.hpp.

int mfcpp::CameraNodelet::n_pxl_height_
private

Nbr of pixels along sensor height.

Definition at line 147 of file camera_nodelet.hpp.

int mfcpp::CameraNodelet::n_pxl_width_
private

Nbr of pixels along sensor width.

Definition at line 148 of file camera_nodelet.hpp.

ros::NodeHandle mfcpp::CameraNodelet::nh_
private

Node handler (for topics and services)

Definition at line 98 of file camera_nodelet.hpp.

float mfcpp::CameraNodelet::noise_decay_
private

Spatial decay rate for measurement noise standard deviation

Definition at line 152 of file camera_nodelet.hpp.

bool mfcpp::CameraNodelet::noise_meas_
private

Whether to noise measurements on disease heatmap.

Definition at line 150 of file camera_nodelet.hpp.

float mfcpp::CameraNodelet::noise_std_
private

Maximum standard deviation of the measurement noise.

Definition at line 151 of file camera_nodelet.hpp.

ros::Publisher mfcpp::CameraNodelet::out_pub_
private

Publisher for the camera output.

Definition at line 102 of file camera_nodelet.hpp.

OverlapCallback mfcpp::CameraNodelet::overlap_cb_
private

Callback instance for overlap detection

Definition at line 131 of file camera_nodelet.hpp.

ros::NodeHandle mfcpp::CameraNodelet::private_nh_
private

Private node handler (for parameters)

Definition at line 99 of file camera_nodelet.hpp.

std::vector<rp3d::CollisionBody*> mfcpp::CameraNodelet::ray_bodies_
private

Collision bodies for raycasting.

Definition at line 124 of file camera_nodelet.hpp.

ros::ServiceServer mfcpp::CameraNodelet::ray_multi_serv_
private

Service for raycasting from several camera poses.

Definition at line 101 of file camera_nodelet.hpp.

std::vector<box_shape_ptr> mfcpp::CameraNodelet::ray_shapes_
private

Collision shapes of algae for raycasting.

Definition at line 127 of file camera_nodelet.hpp.

rp3d::CollisionWorld mfcpp::CameraNodelet::ray_world_
private

World with algae colliding with FOV.

Definition at line 121 of file camera_nodelet.hpp.

RaycastCallback mfcpp::CameraNodelet::raycast_cb_
private

Callback instance for raycasting.

Definition at line 130 of file camera_nodelet.hpp.

geometry_msgs::TransformStamped mfcpp::CameraNodelet::robot_camera_tf_
private

Transform from robot to camera frame.

Definition at line 112 of file camera_nodelet.hpp.

std::string mfcpp::CameraNodelet::robot_frame_
private

Frame of the robot.

Definition at line 139 of file camera_nodelet.hpp.

ros::Publisher mfcpp::CameraNodelet::rviz_pub_
private

Publisher for Rviz markers.

Definition at line 103 of file camera_nodelet.hpp.

float mfcpp::CameraNodelet::sensor_height_
private

Height of the camera sensor.

Definition at line 145 of file camera_nodelet.hpp.

float mfcpp::CameraNodelet::sensor_width_
private

Width of the camera sensor.

Definition at line 144 of file camera_nodelet.hpp.

tf2_ros::Buffer mfcpp::CameraNodelet::tf_buffer_
private

Definition at line 104 of file camera_nodelet.hpp.

tf2_ros::TransformListener mfcpp::CameraNodelet::tf_listener_
private

Definition at line 105 of file camera_nodelet.hpp.

bool mfcpp::CameraNodelet::world_init_
private

Whether the collision world has been initialised.

Definition at line 119 of file camera_nodelet.hpp.

rp3d::WorldSettings mfcpp::CameraNodelet::world_settings_
private

Collision world settings.

Definition at line 122 of file camera_nodelet.hpp.


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