Project

General

Profile

Revision 7a6ed02d

ID7a6ed02d47f49de02afc7e0e8cc97db92054f38c

Added by Thomas Mullins about 12 years ago

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.

View differences:

mikrokopter/src/joystick_control.cpp
27 27

  
28 28
JoystickControl::JoystickControl()
29 29
{
30
  pub = n.advertise<mikrokopter::Control>("/mikrokopter/req_set_control", 100); 
31 30
  sub = n.subscribe<sensor_msgs::Joy>("joy", 100,
32 31
      &JoystickControl::joyCallback, this);
33 32
}
34 33

  
35 34
void JoystickControl::joyLoop()
36 35
{
37
    ros::Rate loop_rate(25);
38
    while(ros::ok())
39
    {
40
        ros::spinOnce(); // if joyCallback is called, it will be in here
41
        control.publish_on(pub);
42
        loop_rate.sleep();
43
    }
44
    return;
36
    control.main_loop();
45 37
}
46 38

  
47 39
void JoystickControl::joyCallback(const sensor_msgs::Joy::ConstPtr& joy)

Also available in: Unified diff