Project

General

Profile

Revision 6ebee82c

ID6ebee82cf91abf048eaf42a61093144dd1743693
Parent bda6eaa0
Child 492d2fde, 673f8af1

Added by Alex Zirbel about 11 years ago

Moved all messages to the messages/ folder.

This meant changing a lot of includes and things.

View differences:

scout/buttons/CMakeLists.txt
17 17
set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
18 18

  
19 19
#uncomment if you have defined messages
20
rosbuild_genmsg()
20
#rosbuild_genmsg()
21 21
#uncomment if you have defined services
22 22
#rosbuild_gensrv()
23 23

  
scout/buttons/manifest.xml
9 9
  <url>https://www.roboticsclub.org/redmine/projects/colonyscout/wiki</url>
10 10
  <depend package="roscpp"/>
11 11
  <depend package="std_msgs"/>
12
  <depend package="messages"/>
12 13

  
13 14
</package>
14 15

  
scout/buttons/msg/button_event.msg
1
bool button1_pressed
2
bool button2_pressed
scout/buttons/src/buttons.cpp
69 69
    /* Advertise that this serves the query_buttons service */
70 70
    ros::NodeHandle n;
71 71

  
72
    ros::Publisher pub = n.advertise<buttons::button_event>("button_event",
73
                                                            QUEUE_SIZE);
72
    ros::Publisher pub = n.advertise< ::messages::button_event>("button_event",
73
                                                                QUEUE_SIZE);
74 74

  
75 75
    /* Initialize hardware for buttons */
76 76
    // Hardware init functions here
scout/buttons/src/buttons.h
38 38
#ifndef _BUTTONS_H_
39 39
#define _BUTTONS_H_
40 40

  
41
#include "buttons/button_event.h"
41
#include <messages/button_event.h>
42 42

  
43 43
#define QUEUE_SIZE 10
44 44
#define BUTTON_PRESSED 0x1
scout/encoders/CMakeLists.txt
19 19
#uncomment if you have defined messages
20 20
#rosbuild_genmsg()
21 21
#uncomment if you have defined services
22
rosbuild_gensrv()
22
#rosbuild_gensrv()
23 23

  
24 24
#common commands for building c++ executables and libraries
25 25
#rosbuild_add_library(${PROJECT_NAME} src/example.cpp)
scout/encoders/manifest.xml
9 9
  <url>https://www.roboticsclub.org/redmine/projects/colonyscout/wiki</url>
10 10
  <depend package="roscpp"/>
11 11
  <depend package="std_msgs"/>
12
  <depend package="messages"/>
12 13

  
13 14
</package>
14 15

  
scout/encoders/src/encoders.cpp
35 35
 **/
36 36

  
37 37
#include <ros/ros.h>
38

  
39 38
#include "encoders.h"
40 39

  
41 40
/**
......
89 88
 * @param req The request. The units that the response should be in.
90 89
 * @param res The response. The fields will be filled with values.
91 90
 */
92
bool handle_encoders_query(encoders::query_encoders::Request  &req,
93
                           encoders::query_encoders::Response &res)
91
bool handle_encoders_query(::messages::query_encoders::Request  &req,
92
                           ::messages::query_encoders::Response &res)
94 93
{
95 94
    /* Put index, velocity, and distance data in message */
96 95
    res.fl_distance = encoder_fl.get_ticks();
scout/encoders/src/encoders.h
36 36
#define _ENCODERS_H_
37 37

  
38 38
#include <fstream>
39
#include "encoders/query_encoders.h"
39
#include <messages/query_encoders.h>
40 40

  
41 41
class Encoder
42 42
{
......
51 51
int main(int argc, char **argv);
52 52

  
53 53
/** @brief Responds to service to query encoder data **/
54
bool handle_encoders_query(encoders::query_encoders::Request  &req,
55
                           encoders::query_encoders::Response &res);
54
bool handle_encoders_query(messages::query_encoders::Request  &req,
55
                           messages::query_encoders::Response &res);
56 56

  
57 57
#endif
scout/encoders/srv/query_encoders.srv
1
---
2
# All units are simply in encoder ticks since encoders were turned on.
3
uint32 fl_distance
4
uint32 fr_distance
5
uint32 bl_distance
6
uint32 br_distance
scout/libscout/src/ButtonControl.cpp
60 60
 * @brief Respond to button events
61 61
 * Processes message and updates private variables
62 62
 */
63
void ButtonControl::event_callback(const buttons::button_event::ConstPtr& msg)
63
void ButtonControl::event_callback(const ::messages::button_event::ConstPtr& msg)
64 64
{
65 65
    button1_value = msg->button1_pressed;
66 66
    button2_value = msg->button2_pressed;
scout/libscout/src/ButtonControl.h
36 36
 * @author Leon Zhang
37 37
 **/
38 38

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

  
42 42
#ifndef _LIBBUTTONS_H_
......
49 49
        ButtonControl(const ros::NodeHandle& libscout_node,
50 50
                      std::string scoutname);
51 51

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

  
54 54
        bool button1_is_pressed();
55 55
        bool button2_is_pressed();
scout/libscout/src/EncodersControl.cpp
43 43
    : node(libscout_node)
44 44
{
45 45
    query_client =
46
        node.serviceClient<encoders::query_encoders>(scoutname+"/query_encoders");
46
        node.serviceClient< ::messages::query_encoders>(scoutname+"/query_encoders");
47 47
}
48 48

  
49 49
/**
......
52 52
encoder_readings EncodersControl::query()
53 53
{
54 54
    // Set scan range
55
    encoders::query_encoders srv;
55
    ::messages::query_encoders srv;
56 56

  
57 57
    encoder_readings cur_readings;
58 58

  
scout/libscout/src/EncodersControl.h
35 35
#define _ENCODERS_CONTROL_H_
36 36

  
37 37
#include <ros/ros.h>
38
#include <encoders/query_encoders.h>
38
#include <messages/query_encoders.h>
39 39

  
40 40
#include "constants.h"
41 41

  
scout/libscout/src/LinesensorControl.cpp
45 45
    : node(libscout_node)
46 46
{
47 47
    query_client =
48
        node.serviceClient<linesensor::query_linesensor>(scoutname+"/query_linesensor");
48
        node.serviceClient< ::messages::query_linesensor>(scoutname+"/query_linesensor");
49 49
}
50 50

  
51 51
/**
......
54 54
vector<uint32_t> LinesensorControl::query()
55 55
{
56 56
    // Set scan range
57
    linesensor::query_linesensor srv;
57
    ::messages::query_linesensor srv;
58 58

  
59 59
    if (!query_client.call(srv))
60 60
    {
scout/libscout/src/LinesensorControl.h
35 35
#define _LINESENSOR_CONTROL_H_
36 36

  
37 37
#include <ros/ros.h>
38
#include <linesensor/query_linesensor.h>
38
#include <messages/query_linesensor.h>
39 39

  
40 40
#include "constants.h"
41 41

  
scout/libscout/src/MotorControl.cpp
50 50
    : node(libscout_node)
51 51
{
52 52
    set_motors_pub =
53
        node.advertise<motors::set_motors>(scoutname + "/set_motors",
53
        node.advertise< ::messages::set_motors>(scoutname + "/set_motors",
54 54
                                           QUEUE_SIZE, true);
55 55
    query_motors_client =
56
        node.serviceClient<motors::query_motors>(scoutname + "/query_motors");
56
        node.serviceClient< ::messages::query_motors>(scoutname + "/query_motors");
57 57
}
58 58

  
59 59
MotorControl::~MotorControl()
......
125 125
{
126 126
    check_which_ok(which);
127 127

  
128
    motors::set_motors msg;
128
    ::messages::set_motors msg;
129 129

  
130 130

  
131 131
    /* Tell the motors node which motors need to be updated */
......
223 223
 */
224 224
float MotorControl::query(int which)
225 225
{
226
    motors::query_motors srv;
226
    ::messages::query_motors srv;
227 227
    if(query_motors_client.call(srv))
228 228
    {
229 229
        switch(which)
scout/libscout/src/MotorControl.h
39 39
#define _MOTOR_CONTROL_H_
40 40

  
41 41
#include <ros/ros.h>
42
#include <motors/query_motors.h>
43
#include <motors/set_motors.h>
42
#include <messages/query_motors.h>
43
#include <messages/set_motors.h>
44 44

  
45 45
#include "constants.h"
46 46

  
scout/linesensor/CMakeLists.txt
19 19
#uncomment if you have defined messages
20 20
#rosbuild_genmsg()
21 21
#uncomment if you have defined services
22
rosbuild_gensrv()
22
#rosbuild_gensrv()
23 23

  
24 24
#common commands for building c++ executables and libraries
25 25
#rosbuild_add_library(${PROJECT_NAME} src/example.cpp)
scout/linesensor/manifest.xml
10 10
  <url>https://www.roboticsclub.org/redmine/projects/colonyscout/wiki</url>
11 11
  <depend package="roscpp"/>
12 12
  <depend package="std_msgs"/>
13
  <depend package="messages"/>
13 14

  
14 15
</package>
15 16

  
scout/linesensor/srv/query_linesensor.srv
1
---
2
# 10-bit unsigned integers, 0 is perfectly white.
3
uint32[] readings
scout/motors/CMakeLists.txt
17 17
set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
18 18

  
19 19
#uncomment if you have defined messages
20
rosbuild_genmsg()
20
#rosbuild_genmsg()
21 21
#uncomment if you have defined services
22
rosbuild_gensrv()
22
#rosbuild_gensrv()
23 23

  
24 24
#common commands for building c++ executables and libraries
25 25
#rosbuild_add_library(${PROJECT_NAME} src/example.cpp)
scout/motors/manifest.xml
9 9
  <url>https://www.roboticsclub.org/redmine/projects/colonyscout/wiki</url>
10 10
  <depend package="roscpp"/>
11 11
  <depend package="std_msgs"/>
12
  <depend package="messages"/>
12 13

  
13 14
  <export>
14 15
    <cpp cflags="-I${prefix}/include" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib"/>
scout/motors/msg/set_motors.msg
1
# Set these to true if the motor should be updated
2
bool fl_set
3
bool fr_set
4
bool bl_set
5
bool br_set
6
bool teleop_ON
7

  
8
# The absolute motor speeds to set
9
int8 fl_speed
10
int8 fr_speed
11
int8 bl_speed
12
int8 br_speed
13

  
14
int8 MAX_SPEED = 100
15
int8 MIN_SPEED = -100
scout/motors/src/motors.cpp
154 154
 * @param msg The message from the set_motors topic, containing speeds and
155 155
 *  motor configuration settings.
156 156
 */
157
void motors_set(const motors::set_motors::ConstPtr& msg)
157
void motors_set(const ::messages::set_motors::ConstPtr& msg)
158 158
{
159 159
    if(msg->fl_set)
160 160
    {
......
184 184
 * @param req The request. The only field is the units requested.
185 185
 * @param res The response. The fields will be filled with values.
186 186
 */
187
bool motors_query(motors::query_motors::Request &req,
188
                  motors::query_motors::Response &res)
187
bool motors_query(::messages::query_motors::Request &req,
188
                  ::messages::query_motors::Response &res)
189 189
{
190 190
    res.fl_speed = motor_fl.get_speed();
191 191
    res.fr_speed = motor_fr.get_speed();
scout/motors/src/motors.h
40 40
#define _MOTORS_H_
41 41

  
42 42
#include <fstream>
43
#include <motors/set_motors.h>
44
#include <motors/query_motors.h>
43
#include <messages/set_motors.h>
44
#include <messages/query_motors.h>
45 45

  
46 46
#define QUEUE_SIZE 10
47 47

  
......
49 49
int main(int argc, char **argv);
50 50

  
51 51
/** @brief Responds to topic to set motor speeds and configs. **/
52
void motors_set(const motors::set_motors::ConstPtr& msg);
52
void motors_set(const messages::set_motors::ConstPtr& msg);
53 53

  
54 54
/** @brief Responds to service to query motor speeds. **/
55
bool motors_query(motors::query_motors::Request &req,
56
                  motors::query_motors::Response &res);
55
bool motors_query(messages::query_motors::Request &req,
56
                  messages::query_motors::Response &res);
57 57

  
58 58
class Motor
59 59
{
scout/motors/srv/query_motors.srv
1
---
2
int8 fl_speed
3
int8 fr_speed
4
int8 bl_speed
5
int8 br_speed
scout/power/CMakeLists.txt
17 17
set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
18 18

  
19 19
#uncomment if you have defined messages
20
rosbuild_genmsg()
20
#rosbuild_genmsg()
21 21
#uncomment if you have defined services
22
rosbuild_gensrv()
22
#rosbuild_gensrv()
23 23

  
24 24
#common commands for building c++ executables and libraries
25 25
#rosbuild_add_library(${PROJECT_NAME} src/example.cpp)
scout/power/manifest.xml
9 9
  <url>https://www.roboticsclub.org/redmine/projects/colonyscout/wiki</url>
10 10
  <depend package="roscpp"/>
11 11
  <depend package="std_msgs"/>
12
  <depend package="messages"/>
12 13

  
13 14
</package>
14 15

  
scout/power/msg/power_state_changed.msg
1
#32-bit integer with current voltage info
2
uint32 voltage
3
#power percentage [0-100]
4
uint32 percentage
5
#current draw in mW
6
uint32 draw
7
#are we on external power?
8
bool externalpower
9
#is the battery at a warning state?
10
bool warning
11
#is the battery at a critical state?
12
bool critical
13

  
scout/power/src/power.cpp
71 71
 * @param req The request. There are no fields
72 72
 * @param res The response. The fields will be filled with values.
73 73
 */
74
bool power_query(power::query_power::Request &req,
75
                  power::query_power::Response &res)
74
bool power_query(::messages::query_power::Request &req,
75
                 ::messages::query_power::Response &res)
76 76
{
77 77
    res.voltage = voltage;
78 78
    res.percentage = percentage;
scout/power/src/power.h
37 37
#ifndef _POWER_H_
38 38
#define _POWER_H_
39 39

  
40
#include "power/query_power.h"
40
#include <messages/query_power.h>
41 41

  
42 42
/** @brief Initialize the power module and driver. **/
43 43
int main(int argc, char **argv);
44 44

  
45 45
/** @brief Responds to service to query power informatio **/
46
bool power_query(power::query_power::Request &req,
47
                  power::query_power::Response &res);
46
bool power_query(messages::query_power::Request &req,
47
                 messages::query_power::Response &res);
48 48

  
49 49
/** @breif Function that sends the power_state_changed message **/
50 50
void send_power_state_changed();
scout/power/srv/query_power.srv
1
---
2
#32-bit integer with current voltage info
3
uint32 voltage
4
#power percentage [0-100]
5
uint32 percentage
6
#current draw in mW
7
uint32 draw
8
#are we on external power?
9
bool externalpower
10
#is the battery at a warning state?
11
bool warning
12
#is the battery at a critical state?
13
bool critical
scout/scoutsim/manifest.xml
13 13
  <depend package="roslib"/>
14 14
  <depend package="rosconsole"/>
15 15
  <depend package="std_srvs"/>
16
  <depend package="motors" />
17
  <depend package="encoders" />
18
  <depend package="linesensor" />
19 16
  <depend package="geometry_msgs" />
20 17
  <depend package="messages"/>
21 18
  
......
34 31
    <depend package="roslib"/>
35 32
    <depend package="rosconsole"/>
36 33
    <depend package="std_srvs"/>
37
    <depend package="motors" />
38
    <depend package="encoders" />
39 34
    <depend package="geometry_msgs" />
40 35
    <depend package="messages"/>
41 36

  
scout/scoutsim/src/scout.cpp
134 134
     * request.
135 135
     * @todo Use "callback" in all callback function names? Or remove?
136 136
     */
137
    void Scout::setMotors(const motors::set_motors::ConstPtr& msg)
137
    void Scout::setMotors(const ::messages::set_motors::ConstPtr& msg)
138 138
    {
139 139
        last_command_time = ros::WallTime::now();
140 140

  
......
244 244
        return true;
245 245
    }
246 246

  
247
    bool Scout::query_encoders_callback(encoders::query_encoders::Request&,
248
                                        encoders::query_encoders::Response& res)
247
    bool Scout::query_encoders_callback(::messages::query_encoders::Request&,
248
                                        ::messages::query_encoders::Response& res)
249 249
    {
250 250
        res.fl_distance = fl_ticks;
251 251
        res.fr_distance = fr_ticks;
......
255 255
        return true;
256 256
    }
257 257

  
258
    bool Scout::query_linesensor_callback(linesensor::query_linesensor::Request&,
259
                                          linesensor::query_linesensor::Response& res)
258
    bool Scout::query_linesensor_callback(::messages::query_linesensor::Request&,
259
                                          ::messages::query_linesensor::Response& res)
260 260
    {
261 261
        res.readings = linesensor_readings;
262 262

  
scout/scoutsim/src/scout.h
52 52
#include <vector>
53 53
#include <boost/shared_ptr.hpp>
54 54

  
55
#include <motors/set_motors.h>
56
#include <encoders/query_encoders.h>
57
#include <linesensor/query_linesensor.h>
55
#include <messages/set_motors.h>
56
#include <messages/query_encoders.h>
57
#include <messages/query_linesensor.h>
58 58
#include <messages/sonar_distance.h>
59 59
#include <messages/sonar_toggle.h>
60 60
#include <messages/sonar_set_scan.h>
......
124 124

  
125 125
        private:
126 126
            float absolute_to_mps(int absolute_speed);
127
            void setMotors(const motors::set_motors::ConstPtr& msg);
127
            void setMotors(const messages::set_motors::ConstPtr& msg);
128 128
            bool setPenCallback(scoutsim::SetPen::Request&,
129 129
                                scoutsim::SetPen::Response&);
130
            bool query_encoders_callback(encoders::query_encoders::Request&,
131
                                         encoders::query_encoders::Response&);
132
            bool query_linesensor_callback(linesensor::query_linesensor::Request&,
133
                                           linesensor::query_linesensor::Response&);
130
            bool query_encoders_callback(messages::query_encoders::Request&,
131
                                     messages::query_encoders::Response&);
132
            bool query_linesensor_callback(messages::query_linesensor::Request&,
133
                                     messages::query_linesensor::Response&);
134 134
            bool handle_sonar_toggle(messages::sonar_toggle::Request  &req,
135 135
                                     messages::sonar_toggle::Response &res);
136 136
            bool handle_sonar_set_scan(messages::sonar_set_scan::Request  &req,
137
                                       messages::sonar_set_scan::Response &res);
137
                                     messages::sonar_set_scan::Response &res);
138 138
            unsigned int rgb_to_grey(unsigned char r,
139 139
                                     unsigned char g,
140 140
                                     unsigned char b);
scout/scoutsim/src/scout_constants.h
48 48
#ifndef _SCOUTSIM_SCOUT_CONSTANTS_
49 49
#define _SCOUTSIM_SCOUT_CONSTANTS_
50 50

  
51
#include <motors/set_motors.h>
51
#include <messages/set_motors.h>
52 52

  
53 53
/// TODO put these in a utility file somewhere?
54 54
#define min(x,y) ((x < y) ? x : y)
......
57 57
namespace scoutsim
58 58
{
59 59
    // Maximum speed which will be sent to scoutsim in absolute units
60
    const int MAX_ABSOLUTE_SPEED = motors::set_motors::MAX_SPEED;
61
    const int MIN_ABSOLUTE_SPEED = motors::set_motors::MIN_SPEED;
60
    const int MAX_ABSOLUTE_SPEED = messages::set_motors::MAX_SPEED;
61
    const int MIN_ABSOLUTE_SPEED = messages::set_motors::MIN_SPEED;
62 62

  
63 63
    // Speed in m/s corresponding to maximum absolute speed
64 64
    const float MAX_SPEED_MPS = 1.0;
scout/scoutsim/src/sim_frame.cpp
132 132
        teleop_r_speed = 0;
133 133
        teleop_scoutname = "scout1";
134 134

  
135
        teleop_pub = nh.advertise<motors::set_motors>("/scout1/set_motors", 1000);
135
        teleop_pub = nh.advertise< ::messages::set_motors>("/scout1/set_motors", 1000);
136 136

  
137 137
        ROS_INFO("Starting scoutsim with node name %s",
138 138
                 ros::this_node::getName().c_str()) ;
......
241 241
    {
242 242
        std::stringstream ss;
243 243
        ss << "/" << req.scout_name << "/set_motors";
244
        teleop_pub = nh.advertise<motors::set_motors>(ss.str(), 1000);
244
        teleop_pub = nh.advertise< ::messages::set_motors>(ss.str(), 1000);
245 245
        teleop_scoutname = req.scout_name.c_str();
246 246
        ROS_INFO("Teleoping %s...",teleop_scoutname.c_str()); //debug statement
247 247

  
......
532 532
                break;
533 533
        }
534 534

  
535
        motors::set_motors msg;
535
        ::messages::set_motors msg;
536 536
        msg.fl_set = true;
537 537
        msg.fr_set = true;
538 538
        msg.bl_set = true;
scout/scoutsim/src/sim_frame.h
61 61
#include <scoutsim/SetSonarViz.h>
62 62
#include <scoutsim/SetGhost.h>
63 63
#include <scoutsim/SetTeleop.h>
64
#include <motors/set_motors.h>
64
#include <messages/set_motors.h>
65 65
#include <map>
66 66

  
67 67
#include "scout.h"

Also available in: Unified diff