Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
jsk_pcl_ros_utils::SphericalPointCloudSimulator Class Reference

This is a class for jsk_pcl/SphericalPointCloudSimulator nodelet. More...

#include <spherical_pointcloud_simulator.h>

Inheritance diagram for jsk_pcl_ros_utils::SphericalPointCloudSimulator:
Inheritance graph
[legend]

Public Types

typedef SphericalPointCloudSimulatorConfig Config
 
- Public Types inherited from jsk_topic_tools::DiagnosticNodelet
typedef boost::shared_ptr< DiagnosticNodeletPtr
 

Public Member Functions

 SphericalPointCloudSimulator ()
 
- Public Member Functions inherited from jsk_topic_tools::DiagnosticNodelet
 DiagnosticNodelet (const std::string &name)
 
- Public Member Functions inherited from jsk_topic_tools::ConnectionBasedNodelet
 ConnectionBasedNodelet ()
 
- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
virtual ~Nodelet ()
 

Protected Member Functions

virtual void configCallback (Config &config, uint32_t level)
 dynamic_reconfigure callback More...
 
virtual void generate (const sensor_msgs::PointCloud2::ConstPtr &msg)
 Callback function for ~input topic. More...
 
virtual Eigen::Affine3f getPlane (double phi)
 Transformation for scan plane specified by phi angle. More...
 
virtual pcl::PointXYZ getPoint (double r, double theta, const Eigen::Affine3f &trans)
 compute a point according to a parametric model of spherical tilting laser. More...
 
virtual void onInit ()
 Initialization function. More...
 
virtual void subscribe ()
 Subscribe another pointcloud to synchronize timestamp. More...
 
virtual void timerCallback (const ros::TimerEvent &event)
 Timer callback for fixed rate publishing. More...
 
virtual void unsubscribe ()
 Shutdown subscribers. More...
 
- Protected Member Functions inherited from jsk_topic_tools::DiagnosticNodelet
virtual void updateDiagnostic (diagnostic_updater::DiagnosticStatusWrapper &stat)
 
- Protected Member Functions inherited from jsk_topic_tools::ConnectionBasedNodelet
ros::Publisher advertise (ros::NodeHandle &nh, std::string topic, int queue_size)
 
image_transport::CameraPublisher advertiseCamera (ros::NodeHandle &nh, image_transport::ImageTransport &it, const std::string &topic, int queue_size)
 
image_transport::CameraPublisher advertiseCamera (ros::NodeHandle &nh, const std::string &topic, int queue_size)
 
image_transport::Publisher advertiseImage (ros::NodeHandle &nh, image_transport::ImageTransport &it, const std::string &topic, int queue_size)
 
image_transport::Publisher advertiseImage (ros::NodeHandle &nh, const std::string &topic, int queue_size)
 
virtual void cameraConnectionBaseCallback ()
 
virtual void cameraConnectionCallback (const image_transport::SingleSubscriberPublisher &pub)
 
virtual void cameraInfoConnectionCallback (const ros::SingleSubscriberPublisher &pub)
 
virtual void connectionCallback (const ros::SingleSubscriberPublisher &pub)
 
virtual void imageConnectionCallback (const image_transport::SingleSubscriberPublisher &pub)
 
virtual bool isSubscribed ()
 
virtual void onInitPostProcess ()
 
virtual void warnNeverSubscribedCallback (const ros::WallTimerEvent &event)
 
virtual void warnOnInitPostProcessCalledCallback (const ros::WallTimerEvent &event)
 
- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::string & getName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 

Protected Attributes

double fps_
 
std::string frame_id_
 frame_id of output pointcloud. If it is empty string, frame_id of ~input is copied. More...
 
double max_phi_
 
double min_phi_
 
boost::mutex mutex_
 
ros::Publisher pub_
 
double r_
 
double rotate_velocity_
 
int scan_num_
 
double scan_range_
 
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
 
ros::Subscriber sub_
 
ros::Timer timer_
 
- Protected Attributes inherited from jsk_topic_tools::DiagnosticNodelet
TimeredDiagnosticUpdater::Ptr diagnostic_updater_
 
const std::string name_
 
jsk_topic_tools::VitalChecker::Ptr vital_checker_
 
- Protected Attributes inherited from jsk_topic_tools::ConnectionBasedNodelet
bool always_subscribe_
 
std::vector< image_transport::CameraPublishercamera_publishers_
 
boost::mutex connection_mutex_
 
ConnectionStatus connection_status_
 
bool ever_subscribed_
 
std::vector< image_transport::Publisherimage_publishers_
 
boost::shared_ptr< ros::NodeHandlenh_
 
bool on_init_post_process_called_
 
boost::shared_ptr< ros::NodeHandlepnh_
 
std::vector< ros::Publisherpublishers_
 
bool subscribed_
 
ros::WallTimer timer_warn_never_subscribed_
 
ros::WallTimer timer_warn_on_init_post_process_called_
 
bool verbose_connection_
 

Detailed Description

This is a class for jsk_pcl/SphericalPointCloudSimulator nodelet.

Definition at line 51 of file spherical_pointcloud_simulator.h.

Member Typedef Documentation

typedef SphericalPointCloudSimulatorConfig jsk_pcl_ros_utils::SphericalPointCloudSimulator::Config

Definition at line 54 of file spherical_pointcloud_simulator.h.

Constructor & Destructor Documentation

jsk_pcl_ros_utils::SphericalPointCloudSimulator::SphericalPointCloudSimulator ( )
inline

Definition at line 55 of file spherical_pointcloud_simulator.h.

Member Function Documentation

void jsk_pcl_ros_utils::SphericalPointCloudSimulator::configCallback ( Config config,
uint32_t  level 
)
protectedvirtual

dynamic_reconfigure callback

Definition at line 74 of file spherical_pointcloud_simulator_nodelet.cpp.

void jsk_pcl_ros_utils::SphericalPointCloudSimulator::generate ( const sensor_msgs::PointCloud2::ConstPtr &  msg)
protectedvirtual

Callback function for ~input topic.

Pointcloud message is used only for timestamp and frame_id.

Definition at line 96 of file spherical_pointcloud_simulator_nodelet.cpp.

Eigen::Affine3f jsk_pcl_ros_utils::SphericalPointCloudSimulator::getPlane ( double  phi)
protectedvirtual

Transformation for scan plane specified by phi angle.

Definition at line 130 of file spherical_pointcloud_simulator_nodelet.cpp.

pcl::PointXYZ jsk_pcl_ros_utils::SphericalPointCloudSimulator::getPoint ( double  r,
double  theta,
const Eigen::Affine3f &  trans 
)
protectedvirtual

compute a point according to a parametric model of spherical tilting laser.

The normal of scan plane is defined as [0, sin(phi), cos(phi)]. Each point of scan is represented as follows respected to the plane: p = [r*cos(theta), r*sin(theta), 0]

Definition at line 140 of file spherical_pointcloud_simulator_nodelet.cpp.

void jsk_pcl_ros_utils::SphericalPointCloudSimulator::onInit ( void  )
protectedvirtual

Initialization function.

Reimplemented from jsk_topic_tools::DiagnosticNodelet.

Definition at line 40 of file spherical_pointcloud_simulator_nodelet.cpp.

void jsk_pcl_ros_utils::SphericalPointCloudSimulator::subscribe ( )
protectedvirtual

Subscribe another pointcloud to synchronize timestamp.

Implements jsk_topic_tools::ConnectionBasedNodelet.

Definition at line 63 of file spherical_pointcloud_simulator_nodelet.cpp.

void jsk_pcl_ros_utils::SphericalPointCloudSimulator::timerCallback ( const ros::TimerEvent event)
protectedvirtual

Timer callback for fixed rate publishing.

Definition at line 86 of file spherical_pointcloud_simulator_nodelet.cpp.

void jsk_pcl_ros_utils::SphericalPointCloudSimulator::unsubscribe ( )
protectedvirtual

Shutdown subscribers.

Implements jsk_topic_tools::ConnectionBasedNodelet.

Definition at line 69 of file spherical_pointcloud_simulator_nodelet.cpp.

Member Data Documentation

double jsk_pcl_ros_utils::SphericalPointCloudSimulator::fps_
protected

Definition at line 126 of file spherical_pointcloud_simulator.h.

std::string jsk_pcl_ros_utils::SphericalPointCloudSimulator::frame_id_
protected

frame_id of output pointcloud. If it is empty string, frame_id of ~input is copied.

Definition at line 117 of file spherical_pointcloud_simulator.h.

double jsk_pcl_ros_utils::SphericalPointCloudSimulator::max_phi_
protected

Definition at line 124 of file spherical_pointcloud_simulator.h.

double jsk_pcl_ros_utils::SphericalPointCloudSimulator::min_phi_
protected

Definition at line 123 of file spherical_pointcloud_simulator.h.

boost::mutex jsk_pcl_ros_utils::SphericalPointCloudSimulator::mutex_
protected

Definition at line 108 of file spherical_pointcloud_simulator.h.

ros::Publisher jsk_pcl_ros_utils::SphericalPointCloudSimulator::pub_
protected

Definition at line 110 of file spherical_pointcloud_simulator.h.

double jsk_pcl_ros_utils::SphericalPointCloudSimulator::r_
protected

Definition at line 122 of file spherical_pointcloud_simulator.h.

double jsk_pcl_ros_utils::SphericalPointCloudSimulator::rotate_velocity_
protected

Definition at line 118 of file spherical_pointcloud_simulator.h.

int jsk_pcl_ros_utils::SphericalPointCloudSimulator::scan_num_
protected

Definition at line 127 of file spherical_pointcloud_simulator.h.

double jsk_pcl_ros_utils::SphericalPointCloudSimulator::scan_range_
protected

Definition at line 125 of file spherical_pointcloud_simulator.h.

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros_utils::SphericalPointCloudSimulator::srv_
protected

Definition at line 111 of file spherical_pointcloud_simulator.h.

ros::Subscriber jsk_pcl_ros_utils::SphericalPointCloudSimulator::sub_
protected

Definition at line 109 of file spherical_pointcloud_simulator.h.

ros::Timer jsk_pcl_ros_utils::SphericalPointCloudSimulator::timer_
protected

Definition at line 120 of file spherical_pointcloud_simulator.h.


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


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:15