2 #include <pioneer_mrs/CommunicationState.h> 16 comm_state[0].state = {
false,
true,
true,
true,
true};
17 comm_state[1].state = {
true,
false,
true,
true,
true};
18 comm_state[2].state = {
true,
true,
false,
true,
true};
19 comm_state[3].state = {
true,
true,
true,
false,
true};
20 comm_state[4].state = {
true,
true,
true,
true,
false};
21 comm_pub[0] = nh.
advertise<pioneer_mrs::CommunicationState>(
"/robot1/comm_state", 1);
22 comm_pub[1] = nh.
advertise<pioneer_mrs::CommunicationState>(
"/robot2/comm_state", 1);
23 comm_pub[2] = nh.
advertise<pioneer_mrs::CommunicationState>(
"/robot3/comm_state", 1);
24 comm_pub[3] = nh.
advertise<pioneer_mrs::CommunicationState>(
"/robot4/comm_state", 1);
25 comm_pub[4] = nh.
advertise<pioneer_mrs::CommunicationState>(
"/robot5/comm_state", 1);
29 int main(
int argc,
char **argv)
37 for(
int i=0; i<=4; i++)
pioneer_mrs::CommunicationState comm_state[5]
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
Communication(ros::NodeHandle &nh)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher comm_pub[5]