43 #ifndef FASTRACK_SENSOR_SPHERE_SENSOR_H 44 #define FASTRACK_SENSOR_SPHERE_SENSOR_H 48 #include <fastrack_msgs/SensedSpheres.h> 55 E, fastrack_msgs::SensedSpheres, SphereSensorParams> {
83 ros::NodeHandle nl(n);
86 if (!nl.getParam(
"range", this->params_.range))
return false;
95 geometry_msgs::TransformStamped tf;
100 }
catch(tf2::TransformException &ex) {
101 ROS_WARN(
"%s: %s", this->
name_.c_str(), ex.what());
102 ROS_WARN(
"%s: Could not determine current sensor pose.", this->
name_.c_str());
117 visualization_msgs::Marker m;
120 m.header.stamp = ros::Time::now();
122 m.type = visualization_msgs::Marker::SPHERE;
123 m.action = visualization_msgs::Marker::ADD;
SphereSensorParams params_
std::string sensor_frame_
tf2_ros::Buffer tf_buffer_
bool LoadParameters(const ros::NodeHandle &n)