Project

General

Profile

Revision b00761a0

IDb00761a0e88f934a309a939b653d9f441b127ae8
Parent c492be62
Child 4069a378

Added by Alex Zirbel over 12 years ago

Updated ButtonControl and SonarControl.

Finally, the behavior compiles. Had to fix a lot of problems involving misunderstandings with Publisher/Client/ServiceServer/ServiceClient confusion.

We can now run priya_behavior as an executable, though the process for generating behavior executables still needs some work.

View differences:

scout/buttons/src/buttons.cpp
31 31
 *
32 32
 * @author Colony Project, CMU Robotics Club
33 33
 * @author Priyanka Deo
34
 * @author Alex Zirbel
34 35
 **/
35 36

  
36 37
#include "ros/ros.h"
......
50 51
static int button2_pressed; /**< Whether or not button 2 is pressed. */
51 52

  
52 53
/**
53
 * @brief Handles button events
54
 *
55
 * Handles button events based on subscription to the button_event topic.
56
 *
57
 * @param msg The message from the button_event topic, containing buttons
58
 * statuses.
59
 */
60
void event_button(const buttons::button_event::ConstPtr& msg)
61
{
62
    //TODO: What goes here?
63
}
64

  
65

  
66
/**
67
 * @brief Outputs whether or not the buttons are pressed.
68
 *
69
 * Serves the service query_buttons by responding to service requests 
70
 * with the status of the buttons
71
 * @param req The request. The only field is the units requested.
72
 * @param res The response. The fields will be filled with values.
73
 */
74
bool buttons_query(buttons::query_buttons::Request &req,
75
                  buttons::query_buttons::Response &res)
76
{
77
    int units = req.units;
78
    res.button1_pressed = button1_pressed;
79
    res.button2_pressed = button2_pressed;
80

  
81
    ROS_DEBUG("Button status queried");
82
    return true;
83
}
84

  
85

  
86
/**
87 54
 * @brief Buttons driver. This is a ROS node that queries button status.
88 55
 *
89 56
 * This is the main function for the buttons node. It is run
......
93 60
 * 
94 61
 * @param argc The number of command line arguments (should be 1)
95 62
 * @param argv The array of command line arguments
96
 **/
63
 */
97 64
int main(int argc, char **argv)
98 65
{
99 66
    /* Initialize in ROS the buttons driver node */
......
101 68

  
102 69
    /* Advertise that this serves the query_buttons service */
103 70
    ros::NodeHandle n;
104
    ros::ServiceServer service = n.advertiseService("query_buttons",
105
                                                    buttons_query);
106 71

  
107
    /* Subscribe to the button_event topic */
108
    ros::Subscriber sub0 = n.subscribe("button_event", 4, event_button);
72
    ros::Publisher pub = n.advertise<buttons::button_event>("button_event",
73
                                                            QUEUE_SIZE);
109 74

  
110 75
    /* Initialize hardware for buttons */
111 76
    // Hardware init functions here
77
    
78
    // Publish a button event now and then
112 79

  
113
    ROS_INFO("Ready to query buttons.");
80
    ROS_INFO("Ready to handle buttons. [unimplemented]");
114 81
    ros::spin();
115 82

  
116 83
    return 0;
scout/buttons/src/buttons.h
32 32
 *
33 33
 * @author Colony Project, CMU Robotics Club
34 34
 * @author Priyanka Deo
35
 **/
35
 * @author Alex Zirbel
36
 */
36 37

  
37 38
#ifndef _BUTTONS_H_
38 39
#define _BUTTONS_H_
39 40

  
40
#include "buttons/query_buttons.h"
41 41
#include "buttons/button_event.h"
42 42

  
43
#define QUEUE_SIZE 10
43 44
#define BUTTON_PRESSED 0x1
44 45

  
45 46
/** @brief Initialize the buttons module and driver. **/
46 47
int main(int argc, char **argv);
47 48

  
48
/** @brief Responds to topic to notify of button events. **/
49
void event_button(const buttons::button_event::ConstPtr& msg);
50

  
51
/** @brief Responds to service to query buttons. **/
52
bool buttons_query(buttons::query_buttons::Request &req,
53
                  buttons::query_buttons::Response &res);
54

  
55 49
#endif
scout/buttons/srv/query_buttons.srv
1
int8 units
2
---
3
bool button1_pressed
4
bool button2_pressed
scout/libscout/CMakeLists.txt
29 29
#rosbuild_add_executable(example examples/example.cpp)
30 30
#target_link_libraries(example ${PROJECT_NAME})
31 31

  
32
rosbuild_add_executable(priya_behavior src/priya_behavior_process.cpp src/PriyaBehavior.cpp src/Behavior.cpp src/MotorControl.cpp src/HeadlightControl.cpp src/ButtonControl.cpp)
32
rosbuild_add_executable(priya_behavior src/priya_behavior_process.cpp src/PriyaBehavior.cpp src/Behavior.cpp src/MotorControl.cpp src/SonarControl.cpp src/HeadlightControl.cpp src/ButtonControl.cpp)
scout/libscout/src/ButtonControl.cpp
34 34
 * @author Colony Project, CMU Robotics Club
35 35
 * @author Priyanka Deo
36 36
 * @author Leon Zhang
37
 * @author Alex Zirbel
37 38
 **/
38 39

  
39 40
#include "ButtonControl.h"
40 41

  
41
/*!
42
using namespace std;
43

  
44
/**
42 45
 * @brief Initialize the buttons module of libscout.
43 46
 *
44 47
 * Initialize the libscout node as a subscriber of button_event
45 48
 */
46
ButtonControl::ButtonControl(const ros::NodeHandle& libscout_node) : node(libscout_node)
49
ButtonControl::ButtonControl(const ros::NodeHandle& libscout_node,
50
                             string scoutname)
51
    : node(libscout_node)
47 52
{
48
    button_event_sub = node.subscribe("button_event", QUEUE_SIZE, event_button);
53
    button_event_sub = node.subscribe(scoutname + "/button_event",
54
                                      QUEUE_SIZE,
55
                                      &ButtonControl::event_callback,
56
                                      this);
49 57
}
50 58

  
51
/*!*
59
/**
52 60
 * @brief Respond to button events
53
 * Sends out button events if buttons are pressed. 
54 61
 * Processes message and updates private variables
55
 * 
56
 * @param subscription to button_event message
57 62
 */
58
void ButtonControl::event_button(const buttons::button_event::ConstPtr& msg)
63
void ButtonControl::event_callback(const buttons::button_event::ConstPtr& msg)
59 64
{
60
    button1_pressed = msg.button1_pressed;
61
    button2_pressed = msg.button2_pressed;
65
    button1_value = msg->button1_pressed;
66
    button2_value = msg->button2_pressed;
62 67
}
63 68

  
64 69
/**
65
*@brief check if button 1 is currently being pressed
66
* 
67
*@return true if button is pressed, otherwise false
68
*/
70
 * @brief check if button 1 is currently being pressed
71
 * 
72
 * @return true if button is pressed, otherwise false
73
 */
69 74
bool ButtonControl::button1_is_pressed()
70 75
{
71 76
    return button1_value;
72 77
}
73 78

  
74 79
/**
75
*@brief check if button 2 is currently being pressed
76
* 
77
*@return true if button is pressed, otherwise false
78
*/
80
 * @brief check if button 2 is currently being pressed
81
 * 
82
 * @return true if button is pressed, otherwise false
83
 */
79 84
bool ButtonControl::button2_is_pressed()
80 85
{ 
81 86
    return button2_value;
scout/libscout/src/ButtonControl.h
35 35
 * @author Priyanka Deo
36 36
 * @author Leon Zhang
37 37
 **/
38

  
38 39
#include "buttons/button_event.h"
39 40
#include "constants.h"
40 41

  
......
44 45
class ButtonControl
45 46
{
46 47
    public:
47
        /** set up buttons node and prepare to communicate over ROS**/
48
        ButtonControl(const ros::NodeHandle& libscout_node);
49
        void event_button(const buttons::button_event::ConstPtr& msg);
48
        /** Set up buttons node and prepare to communicate over ROS */
49
        ButtonControl(const ros::NodeHandle& libscout_node,
50
                      std::string scoutname);
51

  
52
        void event_callback(const buttons::button_event::ConstPtr& msg);
50 53

  
51 54
        bool button1_is_pressed();
52 55
        bool button2_is_pressed();
......
55 58
        bool button1_value;
56 59
        bool button2_value;
57 60

  
58
        /* ROS node created in libscout.cpp */
59 61
        ros::NodeHandle node;
60 62

  
61 63
        /** ROS subscriber declaration */
62 64
        ros::Subscriber button_event_sub;
63
    
64
}
65
};
65 66

  
66 67
#endif
scout/libscout/src/SonarControl.cpp
36 36

  
37 37
#include "SonarControl.h"
38 38

  
39
#define MAX_ATTEMPTS 10
40

  
39 41
using namespace std;
40 42

  
41 43
/**
......
48 50
                           string scoutname)
49 51
    : node(libscout_node)
50 52
{
51
    sonar_set_scan_pub =
52
        node.advertise<sonar::sonar_set_scan>(scoutname + "/set_sonar_scan",
53
                                              QUEUE_SIZE);
54
    sonar_toggle_pub = 
55
        node.advertise<sonar::sonar_toggle>(scoutname + "/toggle_sonar",
56
                                            QUEUE_SIZE);
57
    sonar_distance_sub = node.subscribe(scoutname + "sonar_distance",
58
                                        QUEUE_SIZE, distance_callback);
53
    sonar_set_scan_client =
54
        node.serviceClient<sonar::sonar_set_scan>(scoutname+"/set_sonar_scan");
55
    sonar_toggle_client = 
56
        node.serviceClient<sonar::sonar_toggle>(scoutname + "/toggle_sonar");
57
    sonar_distance_sub = node.subscribe(scoutname + "/sonar_distance",
58
                                        QUEUE_SIZE,
59
                                        &SonarControl::distance_callback,
60
                                        this);
59 61

  
60 62
    // Initialize all the sonar readings to 0 and timestamps to undefined
61 63
    for (int i = 0; i < 48; i++)
......
63 65
        readings[i] = 0;
64 66
        timestamps[i] = ros::Time::now(); // A common shortcut for no reading
65 67
    }
68

  
69
    /// @todo Test, and replace 10 with a const int
70
    num_attempts = MAX_ATTEMPTS;
66 71
}
67 72

  
68 73
/**
......
88 93
 * @brief Sets the sonar to a position.
89 94
 *
90 95
 * @param position Value between 0-180 of degree position to set sonar
91
 * @return NONE
92
 * @todo should return bool. See below.
93 96
 */
94 97
void SonarControl::set_single(int position)
95 98
{
......
101 104
 *
102 105
 * @param start_pos The leftmost (smallest) value that the sonar can take
103 106
 * @param end_pos The rightmost (largest) value that the sonar can take
104
 * @return NONE
105
 * @todo Also misimplemented, should return bool. Look at srv def in sonar/
106 107
 */
107 108
void SonarControl::set_range(int start_pos, int end_pos)
108 109
{
......
121 122
        end_pos = temp;
122 123
    }
123 124

  
124
    // Turn sonar on
125
    sonar::sonar_toggle on_msg;
126
    on_msg.set_on = true;
127
    sonar_toggle_pub.publish(on_msg);
125
    // Make sure sonar is on
126
    set_on();
128 127

  
129 128
    // Set scan range
130
    sonar::sonar_set_scan msg;
131
    msg.stop_l = start_pos;
132
    msg.stop_r = end_pos;
129
    sonar::sonar_set_scan srv;
130
    srv.request.stop_l = start_pos;
131
    srv.request.stop_r = end_pos;
132

  
133
    // Check if the service call failed or if the response was false
134
    if (!sonar_set_scan_client.call(srv) || srv.response.ack == false)
135
    {
136
        if (--num_attempts == 0)
137
        {
138
            ROS_ERROR("SonarControl::set_range() failed permanently.");
139
        }
133 140

  
134
    sonar_set_scan_pub.publish(msg);
135
    ros::spinOnce();  ///<! Sure? Does this belong here?
141
        ROS_WARN("SonarControl::set_range() failed once.");
142
    }
143
}
144

  
145
/**
146
 * @brief Turn on sonar readings
147
 *
148
 * (Re)starts sonar panning and taking readings.
149
 */
150
void SonarControl::set_on()
151
{
152
    set_power(true);
136 153
}
137 154

  
138 155
/**
139 156
 * @brief Turn off sonar readings
140 157
 *
141 158
 * Stops sonar from panning and taking readings.
142
 * @todo Misimplemented. Needs to use a service call and return the ack as bool
159
 */
160
void SonarControl::set_off()
161
{
162
    set_power(false);
163
}
164

  
165
/**
166
 * @brief Turn sonar readings either off or on.
167
 *
168
 * Attempts to turn the readings off or on, num_attempts times.
143 169
 *
144
 * @return NONE
170
 * @param is_on True if power should be set on, false if should be off.
145 171
 */
146
float SonarControl::set_off()
172
void SonarControl::set_power(bool is_on)
147 173
{
148
    sonar::sonar_toggle on_msg;
149
    on_msg.set_on = false;
150
    sonar_toggle_pub.publish(on_msg);
174
    sonar::sonar_toggle srv;
175
    srv.request.set_on = is_on;
176

  
177
    // Check if the service call failed or if the response was false
178
    if (!sonar_toggle_client.call(srv) || srv.response.ack == false)
179
    {
180
        if (--num_attempts == 0)
181
        {
182
            ROS_ERROR("SonarControl::set_power() failed permanently.");
183
        }
184

  
185
        ROS_WARN("SonarControl::set_power() failed once.");
186
    }
187

  
188
    // Reset num_attempts
189
    num_attempts = MAX_ATTEMPTS;
151 190
}
152 191

  
153 192
/**
scout/libscout/src/SonarControl.h
40 40
#include <ros/ros.h>
41 41
#include <sonar/sonar_set_scan.h>
42 42
#include <sonar/sonar_toggle.h>
43
#include <sonar/sonar_direction.h>
43
#include <sonar/sonar_distance.h>
44

  
45
#include "constants.h"
44 46

  
45 47
class SonarControl
46 48
{
......
49 51
        SonarControl(const ros::NodeHandle& libscout_node,
50 52
                     std::string scoutname);
51 53

  
52
        /** Sets sonar to a position (0-180 deg) specified by input */
54
        /** Sets sonar to a position (0-23) specified by input */
53 55
        void set_single(int position);
54 56

  
55
        /** Sets sonar to scan a range in 0-180 specified by input */
57
        /** Sets sonar to scan a range in 0-23 specified by input */
56 58
        void set_range(int start_pos, int end_pos);
57 59

  
60
        /** (Re)starts sonar panning and taking readings */
61
        void set_on();
62

  
58 63
        /** Stops sonar from panning and taking readings */
59 64
        void set_off();	
60
    
65

  
61 66
    private:
62 67
        /** Record the new sonar distance measurement */
63 68
        void distance_callback(const sonar::sonar_distance::ConstPtr& msg);
64 69

  
70
        /** Sends a sonar_toggle message. */
71
        void set_power(bool is_on);
72

  
65 73
        /** Converts between values output by sensor and physical distances */
66 74
        //float sonar_to_dist(float sonar_value);
67 75
        //float dist_to_sonar(float distance);
68 76

  
77
        /** If a service call fails, tries again this many times. */
78
        int num_attempts;
79

  
80
        /** Keep track of the latest readings and their time of receipt.
81
         *  Readings are in millimeters. */
82
        int readings[48];
83
        ros::Time timestamps[48];
84

  
69 85
        /* ROS publisher and client declaration */
70
        ros::Publisher sonar_set_scan_pub;
71
        ros::Publisher sonar_toggle_pub;
86
        ros::ServiceClient sonar_set_scan_client;
87
        ros::ServiceClient sonar_toggle_client;
72 88
        ros::Subscriber sonar_distance_sub;
73 89

  
74 90
        ros::NodeHandle node;
scout/libscout/src/priya_behavior_process.cpp
31 31
 * 
32 32
 * @author Colony Project, CMU Robotics Club
33 33
 * @author Alex Zirbel
34
 **/
34
 */
35 35

  
36 36
#include <ros/ros.h>
37 37
#include "PriyaBehavior.h"
......
42 42
{
43 43
    string scoutname = "";
44 44

  
45
    // Running with no arguments only supports one scout. Check in case
46
    // the user meant to specify a scout in the arguments.
45 47
    if (argc != 2)
46 48
    {
47 49
        cout << "You have started this behavior in hardware mode." << endl
......
54 56
        scoutname = argv[1];
55 57
    }
56 58

  
57
    ros::init(argc, argv, "libscout");
59
    /// @todo Will using argc and argv cause problems? (I don't think so but..)
60
    ros::init(argc, argv, "priya_behavior");
58 61

  
59 62
    PriyaBehavior *behavior = new PriyaBehavior(scoutname);
60 63
    behavior->run();
scout/sonar/src/sonar.cpp
57 57
 **/
58 58
void sonar_init(void)
59 59
{
60
    ROS_INFO("Sonar_init called [unimplemented].");
60 61
    sonar_stepper_pos = 0;
61 62
}
62 63

  
......
66 67
bool handle_sonar_toggle(sonar::sonar_toggle::Request  &req,
67 68
                         sonar::sonar_toggle::Response &res)
68 69
{
69
    if (req.set_on)
70
    if (req.set_on && !is_on)
71
    {
70 72
        ROS_INFO("Turning on the sonar [unimplemented]");
71
    else
73
    }
74
    else if (req.set_off && is_on)
75
    {
72 76
        ROS_INFO("Turning off the sonar [unimplemented]");
77
    }
73 78

  
74 79
    res.ack = true;
75 80

  
scout/sonar/src/sonar.h
37 37
#ifndef _SONAR_H_
38 38
#define _SONAR_H_
39 39

  
40
/** @brief Initialize the sonar in the library module **/
40
/** Initialize the sonar module and drivers **/
41 41
void sonar_init(void);
42 42

  
43
/** @brief Initialize the sonar module and drivers **/
44
void sonar_module_init(void);
43
/** Responds to sonar on/off requests. */
44
bool handle_sonar_toggle(sonar::sonar_toggle::Request  &req,
45
                         sonar::sonar_toggle::Response &res)
45 46

  
46
/** @brief Read raw sonar data from the sonar module. Takes stepper
47
 * position and sensor to read **/
48
int sonar_read_raw(int direction, int sensor);
49

  
50
/** @brief Wrapper for reading sonar data (angle in degrees and distance in
51
 * cm) **/
52
int sonar_read(int direction);
53

  
54
/** @brief Subscribe function to sonar topic **/
55
void sonar_subscribe(int *function());
47
/** Responds to requests which set the scan range. */
48
bool handle_sonar_set_scan(sonar::sonar_set_scan::Request  &req,
49
                           sonar::sonar_set_scan::Response &res)
56 50

  
57 51
#endif

Also available in: Unified diff