4 #include <cpswarm_msgs/CoverageAction.h> 5 #include <cpswarm_msgs/TargetPositionEvent.h> 39 ROS_INFO(
"Executing local coverage");
60 ROS_INFO(
"Local coverage succeeded, found target %d at [%f, %f]",
result.target_id,
result.target_pose.pose.position.x,
result.target_pose.pose.position.y);
73 ROS_INFO(
"Local coverage preempted");
85 result.target_id = msg->id;
86 result.target_pose = msg->pose;
95 int main (
int argc,
char** argv)
98 init(argc, argv,
"uav_local_coverage");
106 ROS_ERROR(
"Could not set logger level!");
int main(int argc, char **argv)
Main function to be executed by ROS.
actionlib::SimpleActionServer< cpswarm_msgs::CoverageAction > action_server_t
An action server type that allows to start and stop the local coverage task.
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
void found_callback(const cpswarm_msgs::TargetPositionEvent::ConstPtr &msg)
Callback function to receive details of a target that has been detected.
behavior_state_t state
The state of the behavior algorithm.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void ActionCallback(const cpswarm_msgs::CoverageGoalConstPtr &goal, action_server_t *as)
Callback of the action server which executes the local coverage task until it is preempted or finishe...
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
A class that allows to cover a given area using a local search algorithm. The local search performs a...
ROSCPP_DECL const std::string & getName()
cpswarm_msgs::CoverageResult result
The target found during execution of the coverage algorithm.
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
void setPreempted(const Result &result=Result(), const std::string &text=std::string(""))
behavior_state_t step()
Move the swarm member to a new position.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
behavior_state_t
An enumeration for the state of the behavior algorithm.
bool isPreemptRequested()
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
ROSCONSOLE_DECL bool set_logger_level(const std::string &name, levels::Level level)
ROSCPP_DECL void spinOnce()
#define ROSCONSOLE_DEFAULT_NAME