Project

General

Profile

Revision a8480867

IDa84808670408804bf5ce08741a3b59130351928f

Added by Alex Zirbel over 12 years ago

Made a lot of changes to the general structure.

Applied object-orienting techniques to the code, cleaning it up considerably. Major design changes are as follows:

  • All separate node code (ie motors) are meant to only interface with hardware - doing as little logic as possible.
  • Instead, the logic is moved to a class (ie MotorControl) in libscout. PID and other tools should be located here. This significantly reduces dependencies.
  • Files can be included cross-package by being placed in /include/packagename, but this should be avoided to reduce dependencies.

A few formatting changes:

  • Comments should end with / always, not */
  • Use @ instead of \
  • No double newlines.

The motors node is revamped and pretty much correct at this point.

View differences:

scout/motors/src/motors.cpp
33 33
 * @author Ben Wasserman
34 34
 **/
35 35

  
36
#include "ros/ros.h"
37
#include "motors_util.cpp"
38
#include "motors.h"
39
//#include "libscout/src/constants.h"
36
#include <ros/ros.h>
40 37
#include <cstdlib>
38
#include "motors.h"
41 39

  
42 40
/**
43 41
 * @defgroup motors Motors
......
46 44
 * @{
47 45
 **/
48 46

  
49

  
50

  
51 47
/* Motor state variables
52 48
 * Speeds expressed as absolute speed out of max speed (0 - +-MAXSPEED)
53 49
 * Absolute speed is the speed written to the hardware to move the motors
......
69 65
{
70 66
    if(msg->fl_set)
71 67
    {
72
      motor_fl_speed = motors_rel_to_abs(msg->fl_speed, msg->units);
68
      motor_fl_speed = msg->fl_speed;
73 69
    }
74 70
    if(msg->fr_set)
75 71
    {
76
      motor_fr_speed = motors_rel_to_abs(msg->fr_speed, msg->units);
72
      motor_fr_speed = msg->fr_speed;
77 73
    }
78 74
    if(msg->bl_set)
79 75
    {
80
      motor_bl_speed = motors_rel_to_abs(msg->bl_speed, msg->units);
76
      motor_bl_speed = msg->bl_speed;
81 77
    }
82 78
    if(msg->br_set)
83 79
    {
84
      motor_br_speed = motors_rel_to_abs(msg->br_speed, msg->units);
80
      motor_br_speed = msg->br_speed;
85 81
    }
86 82

  
87 83
    /** @todo Add code to write speeds to hardware */
84

  
88 85
    ROS_DEBUG("Motor speeds set");
89 86
}
90 87

  
......
99 96
bool motors_query(motors::query_motors::Request &req,
100 97
                  motors::query_motors::Response &res)
101 98
{
102
    int units = req.units;
103
    res.fl_speed = motors_abs_to_rel(motor_fl_speed, units);
104
    res.fr_speed = motors_abs_to_rel(motor_fr_speed, units);
105
    res.bl_speed = motors_abs_to_rel(motor_bl_speed, units);
106
    res.br_speed = motors_abs_to_rel(motor_br_speed, units);
99
    /** @todo Are we checking hardware or just using the saved values?
100
     *  Saved values sound fine to me (Alex). Pleas confirm. */
101
    res.fl_speed = motor_fl_speed;
102
    res.fr_speed = motor_fr_speed;
103
    res.bl_speed = motor_bl_speed;
104
    res.br_speed = motor_br_speed;
107 105

  
108 106
    ROS_DEBUG("Motor speeds queried");
107

  
109 108
    return true;
110 109
}
111 110

  
......
136 135
    /* Initialize hardware for motors */
137 136
    // Hardware init functions here
138 137

  
139
    ROS_INFO("Ready to set motors.");
138
    ROS_INFO("Motors node ready.");
140 139
    ros::spin();
141 140

  
142 141
    return 0;

Also available in: Unified diff