Project

General

Profile

Revision 6257c97d

ID6257c97dd822231155108c01df3c40200eaa7c12

Added by Alex Zirbel over 11 years ago

Continuing work on standardization of units.

View differences:

scout/motors/msg/set_motors.msg
6 6
bool bl_set
7 7
bool br_set
8 8

  
9
# The absolute motor speeds to set
9
# The absolute motor speeds to set (-255 to 255)
10 10
int8 fl_speed
11 11
int8 fr_speed
12 12
int8 bl_speed
scout/scoutsim/src/scout.cpp
113 113
        sonar_tick_time = ros::Duration(scoutsim::SONAR_HALF_SPIN_TIME / 24.0);
114 114
    }
115 115

  
116
    float Scout::absolute_to_mps(int absolute_speed)
117
    {
118
        return ((float) absolute_speed) * MAX_SPEED_MPS / MAX_ABSOLUTE_SPEED;
119
    }
120

  
116 121
    /**
117 122
     * A callback function that sets velocity based on a set_motors
118 123
     * request.
......
124 129

  
125 130
        if(msg->fl_set)
126 131
        {
127
            motor_fl_speed = msg->fl_speed;
132
            motor_fl_speed = absolute_to_mps(msg->fl_speed);
128 133
        }
129 134
        if(msg->fr_set)
130 135
        {
131
            motor_fr_speed = msg->fr_speed;
136
            motor_fr_speed = absolute_to_mps(msg->fr_speed);
132 137
        }
133 138
        if(msg->bl_set)
134 139
        {
135
            motor_bl_speed = msg->bl_speed;
140
            motor_bl_speed = absolute_to_mps(msg->bl_speed);
136 141
        }
137 142
        if(msg->br_set)
138 143
        {
139
            motor_br_speed = msg->br_speed;
144
            motor_br_speed = absolute_to_mps(msg->br_speed);
140 145
        }
141 146
    }
142 147

  
scout/scoutsim/src/scout.h
121 121
            void paint(wxDC& dc);
122 122

  
123 123
        private:
124
            float absolute_to_mps(int absolute_speed);
124 125
            void setMotors(const motors::set_motors::ConstPtr& msg);
125 126
            bool setPenCallback(scoutsim::SetPen::Request&,
126 127
                                scoutsim::SetPen::Response&);
......
157 158

  
158 159
            /// @todo should these be an array or something?
159 160

  
160
            // Keep track of the last commanded speeds sent to the sim
161
            int motor_fl_speed;
162
            int motor_fr_speed;
163
            int motor_bl_speed;
164
            int motor_br_speed;
161
            // Keep track of the last commanded speeds sent to the sim,
162
            // converted to m/s
163
            float motor_fl_speed;
164
            float motor_fr_speed;
165
            float motor_bl_speed;
166
            float motor_br_speed;
165 167

  
166 168
            // Keep track of encoder ticks for each motor
167 169
            unsigned int fl_ticks;
scout/scoutsim/src/scout_constants.h
45 45
 * OTHER DEALINGS IN THE SOFTWARE.
46 46
 */
47 47

  
48
/// @todo Comment up.
49

  
50 48
namespace scoutsim
51 49
{
50
    // Maximum speed which will be sent to scoutsim in absolute units
51
    const int MAX_ABSOLUTE_SPEED = 255;
52
    // Speed in m/s corresponding to maximum absolute speed
53
    const float MAX_SPEED_MPS = 1.0;
54

  
52 55
    // Pixels in scoutsim per real-world meter.
53 56
    // Note that scout image size has been set based on this.
54 57
    const float PIX_PER_METER = 200.0;
scout/scoutsim/src/sim_frame.cpp
391 391
        }
392 392
        else if (wxGetKeyState(WXK_LEFT))
393 393
        {
394
            teleop_l_speed = -TELEOP_PRECISE_SPEED * 2;
395
            teleop_r_speed = TELEOP_PRECISE_SPEED * 2;
394
            teleop_l_speed = -TELEOP_PRECISE_SPEED;
395
            teleop_r_speed = TELEOP_PRECISE_SPEED;
396 396
        }
397 397
        else if (wxGetKeyState(WXK_RIGHT))
398 398
        {
399
            teleop_l_speed = TELEOP_PRECISE_SPEED * 2;
400
            teleop_r_speed = -TELEOP_PRECISE_SPEED * 2;
399
            teleop_l_speed = TELEOP_PRECISE_SPEED;
400
            teleop_r_speed = -TELEOP_PRECISE_SPEED;
401 401
        }
402 402
    }
403 403

  
scout/scoutsim/src/sim_frame.h
77 77
#define ID_TELEOP_FLUID 9
78 78
#define ID_SONAR 10
79 79

  
80
#define TELEOP_PRECISE_SPEED 1.0f
81
#define TELEOP_FLUID_MAX_SPEED 1.5f
82
#define TELEOP_FLUID_INC 0.1f
80
// Absolute speeds (0 - 255)
81
#define TELEOP_PRECISE_SPEED 160
82
#define TELEOP_FLUID_MAX_SPEED 200
83
#define TELEOP_FLUID_INC 10
83 84

  
84 85
// Teleop types
85 86
#define TELEOP_OFF 0
......
135 136
            ros::Publisher wireless_receive;
136 137

  
137 138
            // Teleop
138
            float teleop_l_speed;
139
            float teleop_r_speed;
139
            int teleop_l_speed;
140
            int teleop_r_speed;
140 141
            ros::Publisher teleop_pub;
141 142
            int teleop_type;
142 143

  
143
            float teleop_fluid_speed;
144
            float teleop_fluid_omega;
144
            int teleop_fluid_speed;
145
            int teleop_fluid_omega;
145 146

  
146 147
            ros::NodeHandle nh;
147 148
            wxTimer* update_timer;

Also available in: Unified diff