55 T
get_param(std::string
const& name, T default_value) {
57 ros::param::param<T>(name, value, default_value);
85 if (num_subscribers > 0) {
86 ROS_DEBUG(
"Publishing data to %d subscribers.", num_subscribers);
100 : cloud_topic(
"cloud_pcd"), file_name(
""), interval(0.0), frame_id(
"base_link"), latch(false)
107 file_name =
get_param(
"~file_name", file_name);
108 interval =
get_param(
"~interval", interval);
109 frame_id =
get_param(
"~frame_id", frame_id);
118 std::stringstream str(argv[2]);
126 if (file_name.empty()) {
131 ROS_ERROR_STREAM(
"Failed to parse pointcloud from file ('" << file_name <<
"')");
143 bool oneshot = interval <= 0;
161 ROS_INFO_STREAM(
" * number of points: " << cloud.width * cloud.height);
167 int main (
int argc,
char** argv) {
169 ros::init(argc, argv,
"pcd_to_pointcloud");
std::string getFieldsList(const sensor_msgs::PointCloud2 &cloud)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool try_load_pointcloud()
void timer_callback(ros::TimerEvent const &)
int main(int argc, char **argv)
void publish(const boost::shared_ptr< M > &message) const
int loadPCDFile(const std::string &file_name, sensor_msgs::PointCloud2 &cloud)
std::string resolveName(const std::string &name, bool remap=true) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
T get_param(std::string const &name, T default_value)
#define ROS_INFO_STREAM(args)
#define ROS_DEBUG_STREAM_ONCE(args)
sensor_msgs::PointCloud2 cloud
#define ROS_ERROR_STREAM(args)
uint32_t getNumSubscribers() const
void parse_cmdline_args(int argc, char **argv)