Project

General

Profile

Revision a8987cda

IDa8987cda5e2c606b2aba534af5ee0edb027c69b3

Added by Thomas Mullins over 11 years ago

Fixes to WirelessReceiver and wl_test

Changed receive callback to use std::function so we can use std::bind to
pass non-static member functions. There is still a weird problem where
WirelessReceiver::dummy gets called many times for each incoming packet
in wl_test.

View differences:

scout/libscout/CMakeLists.txt
36 36
set(CONTROL_CLASSES src/MotorControl.cpp src/SonarControl.cpp src/HeadlightControl.cpp src/ButtonControl.cpp src/WirelessSender.cpp src/WirelessReceiver.cpp src/EncodersControl.cpp src/LinesensorControl.cpp)
37 37

  
38 38
rosbuild_add_executable(libscout ${MAIN_FILES} ${BEHAVIOR_FILES} ${TEST_BEHAVIOR_FILES} ${CONTROL_CLASSES} ${HELPER_FILES})
39
rosbuild_add_compile_flags(libscout -std=c++0x)
39 40
rosbuild_add_executable(test_encoders src/test_encoders.cpp)
scout/libscout/src/WirelessReceiver.cpp
45 45
 * @param libscout_node Node handle of the ROS node used by libscout.
46 46
 **/
47 47
WirelessReceiver::WirelessReceiver(const ros::NodeHandle& libscout_node)
48
    : node(libscout_node)
48
    : node(libscout_node), callback(bind(&WirelessReceiver::dummy, this, _1))
49 49
{
50 50
    sub = node.subscribe("/wireless/receive", QUEUE_SIZE,
51 51
          &WirelessReceiver::receive, this);
......
70 70
 **/
71 71
void WirelessReceiver::receive(const ::messages::WirelessPacketConstPtr& packet)
72 72
{
73
    if (callback == NULL)
74
    {
75
        ROS_WARN("Warning: Ignored wireless packet.");
76
    }
77
    else
78
    {
79
        (*callback)(packet->data);
80
    }
73
    callback(packet->data);
74
}
75

  
76
/**
77
 * @brief The default callback function, to be overwritten by register_callback
78
 */
79
void WirelessReceiver::dummy(std::vector<uint8_t> data) {
80
    ROS_WARN("Warning: Ignored wireless packet.");
81 81
}
scout/libscout/src/WirelessReceiver.h
39 39
#define _WIRELESS_RECEIVER_H_
40 40

  
41 41
#include <vector>
42
#include <functional>
42 43
#include <ros/ros.h>
43 44
#include "messages/WirelessPacket.h"
44 45
#include "constants.h"
45 46

  
46
typedef void (*WirelessCallback)(std::vector<uint8_t>);
47
typedef std::function<void(std::vector<uint8_t>)> WirelessCallback;
47 48

  
48 49
class WirelessReceiver
49 50
{
......
59 60
        ros::NodeHandle node;
60 61
        WirelessCallback callback;
61 62
        void receive(const ::messages::WirelessPacketConstPtr&);
63
        void dummy(std::vector<uint8_t> data);
62 64
};
63 65

  
64 66
#endif
scout/libscout/src/behaviors/wl_test.cpp
25 25

  
26 26
#include "wl_test.h"
27 27

  
28
#define DATA_SIZE 10
29

  
30 28
using namespace std;
31 29

  
32
bool is_receiving = false;
33
uint8_t highest_received = 0;
34

  
35
void data_callback(std::vector<uint8_t> data)
30
void wl_test::data_callback(std::vector<uint8_t> data)
36 31
{
37
    cout << "Wireless callback triggered." << endl;;
38
    for (int i = 0; i < data.size(); i++)
39
    {
40
        if (data[i] > highest_received)
41
        {
42
            highest_received = data[i];
43
        }
44
    }
32
    // We got a response! Stop publishing data = [1]
33
    if (no_response)
34
        no_response = false;
35

  
36
    ROS_INFO("Wireless callback triggered.");
37
    data[0]++;
38
    sleep(1);
39
    wl_sender->send(data,1);
45 40
}
46 41

  
47 42
void wl_test::run()
48 43
{
49
    motors->set_sides(20, 50, MOTOR_ABSOLUTE);
50
    wl_receiver->register_callback(data_callback);
51

  
44
    wl_receiver->register_callback(std::bind(&wl_test::data_callback, this,
45
        std::placeholders::_1));
52 46
    while(ok())
53 47
    {
54
        if (!is_receiving)
48
        // Publish 1 if we are scout1 until we get a response.
49
        if (scout_name == "scout1" && no_response) 
55 50
        {
56
            // Fill up a bogus data array
57
            vector<uint8_t> data;
58
            for (int i = 0; i < DATA_SIZE; i++)
59
            {
60
                data.push_back(highest_received + i);
61
            }
62

  
63
            wl_sender->send(data);
64
            cout << "Sent wireless packet." << endl;
65
            is_receiving = true;
51
            uint8_t data[1];
52
            data[0] = 1;
53
            wl_sender->send(data,1);
66 54
        }
67

  
68 55
        spinOnce();
69 56
        loop_rate->sleep();
70 57
    }
71 58
}
72

  
scout/libscout/src/behaviors/wl_test.h
1
/**
2
 * Copyright (c) 2011 Colony Project
3
 * 
4
 * Permission is hereby granted, free of charge, to any person
5
 * obtaining a copy of this software and associated documentation
6
 * files (the "Software"), to deal in the Software without
7
 * restriction, including without limitation the rights to use,
8
 * copy, modify, merge, publish, distribute, sublicense, and/or sell
9
 * copies of the Software, and to permit persons to whom the
10
 * Software is furnished to do so, subject to the following
11
 * conditions:
12
 * 
13
 * The above copyright notice and this permission notice shall be
14
 * included in all copies or substantial portions of the Software.
15
 * 
16
 * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
17
 * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES
18
 * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
19
 * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT
20
 * HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY,
21
 * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
22
 * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR
23
 * OTHER DEALINGS IN THE SOFTWARE.
24
 */
25

  
26
#ifndef _WL_TEST_H_
27
#define _WL_TEST_H_
28

  
29
#include "../Behavior.h"
30

  
31
class wl_test : Behavior
32
{
33
    public:
34
        wl_test(std::string scoutname) : Behavior(scoutname, "wl_test") {};
35

  
36
        /** Actually executes the behavior. */
37
        void run();
38
};
39

  
40
#endif
1
/**
2
 * Copyright (c) 2011 Colony Project
3
 * 
4
 * Permission is hereby granted, free of charge, to any person
5
 * obtaining a copy of this software and associated documentation
6
 * files (the "Software"), to deal in the Software without
7
 * restriction, including without limitation the rights to use,
8
 * copy, modify, merge, publish, distribute, sublicense, and/or sell
9
 * copies of the Software, and to permit persons to whom the
10
 * Software is furnished to do so, subject to the following
11
 * conditions:
12
 * 
13
 * The above copyright notice and this permission notice shall be
14
 * included in all copies or substantial portions of the Software.
15
 * 
16
 * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
17
 * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES
18
 * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
19
 * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT
20
 * HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY,
21
 * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
22
 * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR
23
 * OTHER DEALINGS IN THE SOFTWARE.
24
 */
25

  
26
#ifndef _WL_TEST_H_
27
#define _WL_TEST_H_
28

  
29
#include "../Behavior.h"
30

  
31
class wl_test : Behavior
32
{
33
    public:
34
        wl_test(std::string scoutname) : Behavior(scoutname, "wl_test"),
35
            no_response(true), scout_name(scoutname) {};
36
        /** Actually executes the behavior. */
37
        void data_callback(std::vector<uint8_t> data);
38
        void run();
39
    private:
40
        bool no_response;
41
        std::string scout_name;
42
};
43

  
44
#endif

Also available in: Unified diff