24 #include <sensor_msgs/PointCloud2.h> 33 const geometry_msgs::Pose b)
35 double dx = a.position.x - b.position.x;
36 double dy = a.position.y - b.position.y;
37 return sqrt(dx*dx + dy*dy);
42 tracking_frame_(
"odom"),
57 float b_arr[] = {0.20657, 0.41314, 0.20657};
58 float a_arr[] = {1.00000, -0.36953, 0.19582};
59 std::vector<float> b(b_arr, b_arr +
sizeof(b_arr)/
sizeof(
float));
60 std::vector<float> a(a_arr, a_arr +
sizeof(a_arr)/
sizeof(
float));
73 for (
double y = -0.15; y <= 0.15; y += 0.001)
75 geometry_msgs::Point p;
82 for (
double x = 0.0; x < 0.05 ; x += 0.001)
84 geometry_msgs::Point p;
140 "Dock orientation invalid.");
142 "Quaternion magnitude is " 144 <<
" Quaternion is [" 145 << q.x() <<
", " << q.y() <<
", " 146 << q.z() <<
", " << q.w() <<
"]" 159 pose.header.frame_id,
183 if (
dock_.header.frame_id ==
"" ||
184 (
dock_.pose.orientation.z == 0.0 &&
dock_.pose.orientation.w == 0.0))
190 for (
size_t i = scan->ranges.size()/2; i < scan->ranges.size(); i++)
192 if (std::isfinite(scan->ranges[i]))
194 double angle = scan->angle_min + i * scan->angle_increment;
195 dock_.header = scan->header;
196 dock_.pose.position.x = cos(angle) * scan->ranges[i];
197 dock_.pose.position.y = sin(angle) * scan->ranges[i];
198 dock_.pose.orientation.x = 1.0;
199 dock_.pose.orientation.y = 0.0;
200 dock_.pose.orientation.z = 0.0;
201 dock_.pose.orientation.w = 0.0;
217 dock_.header.frame_id,
227 ROS_DEBUG_NAMED(
"dock_perception",
"Transformed initial pose to (%f, %f, %f)",
239 std::priority_queue<DockCandidatePtr, std::vector<DockCandidatePtr>,
CompareCandidates> candidates;
240 for (std::list<laser_processor::SampleSet*>::iterator i = processor.
getClusters().begin();
254 geometry_msgs::Pose best_pose;
255 while (!candidates.empty())
257 geometry_msgs::Pose pose =
dock_.pose;
258 double score =
fit(candidates.top(), pose);
261 best = candidates.top();
272 sensor_msgs::PointCloud2 cloud;
273 cloud.header.stamp = scan->header.stamp;
275 cloud.width = cloud.height = 0;
280 cloud_mod.
resize(not_best->points.size());
284 for (
size_t i = 0; i < not_best->points.size(); i++)
286 cloud_iter[0] = not_best->points[i].x;
287 cloud_iter[1] = not_best->points[i].y;
288 cloud_iter[2] = not_best->points[i].z;
310 sensor_msgs::PointCloud2 cloud;
311 cloud.header.stamp = scan->header.stamp;
313 cloud.width = cloud.height = 0;
318 cloud_mod.
resize(best->points.size());
322 for (
size_t i = 0; i < best->points.size(); i++)
324 cloud_iter[0] = best->points[i].x;
325 cloud_iter[1] = best->points[i].y;
326 cloud_iter[2] = best->points[i].z;
336 dock_.header.stamp = scan->header.stamp;
342 dock_.pose = best_pose;
389 for (laser_processor::SampleSet::iterator p = cluster->begin();
393 geometry_msgs::PointStamped pt;
394 pt.header = cluster->
header;
395 pt.point.x = (*p)->x;
396 pt.point.y = (*p)->y;
399 tf_point = t_frame*tf_point;
401 candidate->points.push_back(pt.point);
406 double dx = centroid.x -
dock_.pose.position.x;
407 double dy = centroid.y -
dock_.pose.position.y;
408 candidate->dist = (dx*dx + dy*dy);
417 transform.translation.x = pose.position.x;
418 transform.translation.y = pose.position.y;
419 transform.rotation = pose.orientation;
423 quaternionMsgToTF(pose.orientation, init_pose);
427 "Initial dock orientation estimate is invalid.");
429 "Quaternion magnitude is " 431 <<
" Quaternion is [" 432 << init_pose.x() <<
", " << init_pose.y() <<
", " 433 << init_pose.z() <<
", " << init_pose.w() <<
"]" 440 quaternionMsgToTF(transform.rotation, cand_pose);
444 "Dock candidate orientation estimate is invalid.");
446 "Quaternion magnitude is " 448 <<
" Quaternion is [" 449 << cand_pose.x() <<
", " << cand_pose.y() <<
", " 450 << cand_pose.z() <<
", " << cand_pose.w() <<
"]" 466 quaternionMsgToTF(transform.rotation, cand_pose);
477 transform.translation.x += retry*(0.75/100.0)*
static_cast<double>((rand() % 200) - 100);
478 transform.translation.y += retry*(0.75/100.0)*
static_cast<double>((rand() % 200) - 100);
485 quaternionMsgToTF(transform.rotation, cand_pose);
493 quaternionMsgToTF(transform.rotation, cand_pose);
497 "Dock candidate orientation estimate is invalid.");
500 <<
" Orientation is [" 501 << cand_pose.x() <<
", " << cand_pose.y() <<
", " 502 << cand_pose.z() <<
", " << cand_pose.w() <<
"]" 520 if (candidate->width() < 0.375)
524 transform.rotation = pose.orientation;
531 transform.translation.x,
532 transform.translation.y,
536 pose.position.x = transform.translation.x;
537 pose.position.y = transform.translation.y;
538 pose.position.z = transform.translation.z;
539 pose.orientation = transform.rotation;
551 return 1e-3 >= fabs(1.0 - q.
length());
#define ROS_INFO_NAMED(name,...)
DockPerception(ros::NodeHandle &nh)
static void pointMsgToTF(const geometry_msgs::Point &msg_v, Point &bt_v)
#define ROS_WARN_STREAM_THROTTLE(period, args)
#define ROS_DEBUG_STREAM_NAMED(name, args)
#define ROS_ERROR_STREAM_NAMED(name, args)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
DockCandidatePtr extract(laser_processor::SampleSet *cluster)
Extract a DockCandidate from a cluster, filling in the lengths and slopes of each line found using ra...
double getPoseDistance(const geometry_msgs::Pose a, const geometry_msgs::Pose b)
static double getYaw(const Quaternion &bt_q)
geometry_msgs::PoseStamped dock_
std::vector< geometry_msgs::Point > transform(const std::vector< geometry_msgs::Point > &points, double x, double y, double theta)
Transform a vector of points in 2d.
bool getPose(geometry_msgs::PoseStamped &pose, std::string frame="")
Get the pose of the dock.
ros::Publisher debug_points_
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
std::vector< geometry_msgs::Point > ideal_cloud_
#define ROS_DEBUG_NAMED(name,...)
void publish(const boost::shared_ptr< M > &message) const
std::vector< geometry_msgs::Point > front_cloud_
double alignICP(const std::vector< geometry_msgs::Point > source, const std::vector< geometry_msgs::Point > target, geometry_msgs::Transform &transform, size_t max_iterations=10, double min_delta_rmsd=0.000001)
Perform Iterative Closest Point (ICP) algorithm to align two point clouds in a two dimensional plane...
void splitConnected(float thresh)
static void quaternionMsgToTF(const geometry_msgs::Quaternion &msg, Quaternion &bt)
double max_alignment_error_
bool getParam(const std::string &key, std::string &s) const
double thetaFromQuaternion(const geometry_msgs::Quaternion &q)
Get the 2d rotation from a quaternion.
TFSIMD_FORCE_INLINE Quaternion inverse(const Quaternion &q)
An ordered set of Samples.
ros::Subscriber scan_sub_
geometry_msgs::Point getCentroid(const std::vector< geometry_msgs::Point > points)
Get the centroid of a set of points.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
def normalize_angle(angle)
std::string tracking_frame_
Low pass filter object for filtering dock poses.
std::list< SampleSetConstPtr > & getClusters()
void callback(const sensor_msgs::LaserScanConstPtr &scan)
Callback to process laser scans.
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
#define ROS_INFO_STREAM(args)
static bool isValid(const tf::Quaternion &q)
Method to check if the quaternion is valid.
bool start(const geometry_msgs::PoseStamped &pose)
Start dock detection.
double fit(const DockCandidatePtr &candidate, geometry_msgs::Pose &pose)
Try to fit a dock to candidate.
void removeLessThan(uint32_t num)
LinearPoseFilter2DPtr dock_pose_filter_
A cluster which is a candidate for a dock.
A mask for filtering out Samples based on range.
bool stop()
Stop tracking the dock.
void setPointCloud2FieldsByString(int n_fields,...)
tf::TransformListener listener_
#define ROS_WARN_STREAM_NAMED(name, args)
static void pointTFToMsg(const Point &bt_v, geometry_msgs::Point &msg_v)