Go to the documentation of this file.
   55 T 
get_param(std::string 
const& name, T default_value) {
 
   85         if (num_subscribers > 0) {
 
   86             ROS_DEBUG(
"Publishing data to %d subscribers.", num_subscribers);
 
  118             std::stringstream str(argv[2]);
 
  167 int main (
int argc, 
char** argv) {
 
  169     ros::init(argc, argv, 
"pcd_to_pointcloud");
 
  
#define ROS_ERROR_STREAM(args)
std::string getFieldsList(const sensor_msgs::PointCloud2 &cloud)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
#define ROS_DEBUG_STREAM_ONCE(args)
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
std::string resolveName(const std::string &name, bool remap=true) const
void parse_cmdline_args(int argc, char **argv)
sensor_msgs::PointCloud2 cloud
T get_param(std::string const &name, T default_value)
int loadPCDFile(const std::string &file_name, sensor_msgs::PointCloud2 &cloud)
#define ROS_INFO_STREAM(args)
void timer_callback(ros::TimerEvent const &)
uint32_t getNumSubscribers() const
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
int main(int argc, char **argv)
bool try_load_pointcloud()
pcl_ros
Author(s): Open Perception, Julius Kammerl 
, William Woodall 
autogenerated on Fri Jul 12 2024 02:54:40