7 nh.
param(this_node::getName() +
"/fov_hor",
fov_hor, 1.236);
8 nh.
param(this_node::getName() +
"/fov_ver",
fov_ver, 0.970);
16 double distance, direction;
35 ROS_INFO(
"Reached maximum coverage steps!");
59 double t = sqrt(2 * s / a);
60 double x = a * (cos(t) + t * sin(t));
61 double y = a * (sin(t) - t * cos(t));
64 distance = hypot(x, y);
65 direction = atan2(y, x);
71 double distance, direction;
unsigned int steps
Number of steps performed in the local search.
bool move(geometry_msgs::Pose pose)
double fov_hor
Horizontal camera field of view in radian.
geometry_msgs::Pose select_goal()
Compute goal position.
double altitude
The altitude of the UAV above ground.
uav_local_coverage(double altitude)
Constructor that initializes the private member variables.
geometry_msgs::Pose get_pose() const
double fov_ver
Vertical camera field of view in radian.
behavior_state_t step()
Move the swarm member to a new position.
geometry_msgs::Pose origin
Center of the spiral movement search pattern.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void compute_involute(double &distance, double &direction)
Compute local coordinates on circle involute for current step.
behavior_state_t
An enumeration for the state of the behavior algorithm.
geometry_msgs::Pose compute_goal(double distance, double direction) const
position pos
A helper object for position related tasks.
ROSCPP_DECL void spinOnce()
int max_steps
Maximum number of steps to do in the local search.