39 #include "laser_assembler/AssembleScans2.h" 42 #include "sensor_msgs/PointCloud2.h" 43 #include "sensor_msgs/JointState.h" 86 pub_ = n_.
advertise<sensor_msgs::PointCloud2> (
"full_cloud2", 1);
88 private_ns_.
param(
"num_skips", num_skips_, 0);
93 private_ns_.
param(
"negative_direction", negative_direction_,
false);
96 private_ns_.
param(
"use_tf", use_tf,
false);
102 private_ns_.
param(
"tf_polling_rate", rate_, 30.0);
103 private_ns_.
param(
"spindle_frame", spindle_frame_, std::string(
"multisense/spindle"));
104 private_ns_.
param(
"motor_frame", motor_frame_, std::string(
"multisense/motor"));
126 double yaw =
atan2(t(1,0), t(0,0));
127 sensor_msgs::JointState js;
128 js.header.stamp = transform.
stamp_;
129 js.position.push_back(yaw);
130 const sensor_msgs::JointState js_const (js);
137 double theta = js->position[0];
138 if (negative_direction_) {
141 double ang = fmod(theta, 2 * M_PI);
145 if ( prev_angle_ < 0 ) {
149 if ((ang - prev_angle_) >= - M_PI) {
154 if (prev_signal_.
toSec() == 0.0) {
168 if (num_skips_left_ > 0)
170 num_skips_left_ -= 1;
179 laser_assembler::AssembleScans2::Request req;
180 laser_assembler::AssembleScans2::Response res;
185 ROS_ERROR(
"Failed to call service on point cloud assembler or laser scan assembler.");
188 ROS_DEBUG(
"Snapshotter::Published Cloud size=%u", res.cloud.width * res.cloud.height);
199 int main(
int argc,
char **argv)
201 ros::init(argc, argv,
"spin_laser_snapshotter");
void publish(const boost::shared_ptr< M > &message) const
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3d &e)
Time & fromNSec(uint64_t t)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool call(const std::string &service_name, MReq &req, MRes &res)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void scannerSignalCallback(const sensor_msgs::JointStateConstPtr &js)
ROSCPP_DECL void spin(Spinner &spinner)
std::string spindle_frame_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
void timerCallback(const ros::TimerEvent &event)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_INFO_STREAM(args)
ros::NodeHandle private_ns_
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
tf::TransformListener * listener_
int main(int argc, char **argv)