Revision 7a6ed02d
ID | 7a6ed02d47f49de02afc7e0e8cc97db92054f38c |
Major changes in mikrokopter for lost connection
-In nav_lib.cpp, added main_loop, so we don't have to keep rewriting it
:). Also, this now publishes to /mk_wrapper/control, which should be
used from now on. However, old publish_on still works as it did.
-Changed turn_to_target and joystick_control (but not any others yet) to
use new nav_lib main_loop.
-Added mk_wrapper, which simply copies messages from /mk_wrapper/control
to /mikrokopter/req_set_control. After recieving the first message, if
it receives no message for a period of 200ms (rosparam max_quiet_time),
it will instead publish 0's and a thrust of 60, ignoring all future
input until restarted.
-Added launch files onboard.launch and joystick.launch, so that we
remember what should run where and can easily set some parameters.
mikrokopter/src/nav_lib.h | ||
---|---|---|
13 | 13 |
void set_thrust(float thrust); |
14 | 14 |
void set_yaw(float yaw); |
15 | 15 |
void publish_on(ros::Publisher& pub); |
16 |
void main_loop(); |
|
16 | 17 |
private: |
17 | 18 |
mikrokopter::Control control; |
19 |
ros::NodeHandle nh; |
|
18 | 20 |
}; |
Also available in: Unified diff