Go to the documentation of this file.
   37   tf_listener_(tf_buffer_), waiting_(false)
 
   48   std::string topic_name;
 
   49   nh.
param<std::string>(
"topic", topic_name, 
"/scan");
 
  120   sensor_msgs::PointCloud2 cloud;
 
  147   size_t line_point_count = 0;
 
  148   for (
size_t i = 0; i < 
scan_.ranges.size(); ++i)
 
  151     if (!std::isfinite(
scan_.ranges[i]))
 
  160     geometry_msgs::PointStamped p;
 
  174       geometry_msgs::PointStamped p_out;
 
  178         p.header.frame_id = 
scan_.header.frame_id;
 
  197       (cloud_iter + line_point_count)[
X] = p_out.point.x;
 
  198       (cloud_iter + line_point_count)[
Y] = p_out.point.y;
 
  199       (cloud_iter + line_point_count)[
Z] = p_out.point.z;
 
  206   cloud.width  = line_point_count;
 
  210                                     robot_calibration_msgs::CalibrationData * msg)
 
  212   if (
static_cast<int>(cloud.width) == 0)
 
  214     ROS_WARN(
"No points in observation, skipping");
 
  221   sensor_msgs::PointCloud2 viz_cloud;
 
  223   viz_cloud.height = 0;
 
  225   viz_cloud.header.frame_id = cloud.header.frame_id;
 
  228   cloud_mod.
resize(cloud.width);
 
  231   int idx_cam = msg->observations.size();
 
  232   msg->observations.resize(msg->observations.size() + 1);
 
  238   for (
size_t i = 0; i < cloud.width; ++i)
 
  241     geometry_msgs::PointStamped rgbd;
 
  242     rgbd.point.x = (xyz + i)[
X];
 
  243     rgbd.point.y = (xyz + i)[
Y];
 
  244     rgbd.point.z = (xyz + i)[
Z];
 
  247     msg->observations[idx_cam].features.push_back(rgbd);
 
  250     viz_cloud_iter[0] = rgbd.point.x;
 
  251     viz_cloud_iter[1] = rgbd.point.y;
 
  252     viz_cloud_iter[2] = rgbd.point.z;
 
  259     msg->observations[idx_cam].cloud = cloud;
 
  
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
virtual bool find(robot_calibration_msgs::CalibrationData *msg)
Once the robot has been moved into the proper position and settled, this function will be called....
std::string laser_sensor_name_
Base class for a feature finder.
tf2_ros::Buffer tf_buffer_
The scan finder is useful for aligning a laser scanner with other sensors. In particular,...
sensor_msgs::LaserScan scan_
ROSCPP_DECL void spinOnce()
virtual bool init(const std::string &name, ros::NodeHandle &n)
Initialize the feature finder.
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
ros::Publisher publisher_
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void extractPoints(sensor_msgs::PointCloud2 &cloud)
Extract a point cloud from laser scan points that meet criteria.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
#define ROS_INFO_STREAM(args)
virtual bool init(const std::string &name, ros::NodeHandle &nh)
Initialize the feature finder.
std::string getName()
Get the name of this feature finder.
B & transform(const A &in, B &out, const std::string &target_frame, const ros::Time &target_time, const std::string &fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const
virtual void scanCallback(const sensor_msgs::LaserScan &scan)
ROS callback - updates scan_ and resets waiting_ to false.
Calibration code lives under this namespace.
void extractObservation(const sensor_msgs::PointCloud2 &cloud, robot_calibration_msgs::CalibrationData *msg)
Extract the point cloud into a calibration message.
T param(const std::string ¶m_name, const T &default_val) const
virtual bool waitForScan()
Wait until a new scan has arrived.
std::string transform_frame_
ros::Subscriber subscriber_
void setPointCloud2FieldsByString(int n_fields,...)
robot_calibration
Author(s): Michael Ferguson
autogenerated on Fri Sep 1 2023 02:52:01