Project

General

Profile

Statistics
| Branch: | Revision:

root / mikrokopter / mikrokopter / src / externctrl_client.cpp @ 98711613

History | View | Annotate | Download (1.27 KB)

1 07ec0a21 Chris Burchhardt
 /*!
2
  *  \file    externctrl_client.cpp
3
  *  \brief   A demonstration of the MikrokopterInterface class
4
  *  \author  Andrew Chambers <achamber@andrew.cmu.edu>
5
  *  \author  Justin Haines   <jhaines@andrew.cmu.edu>
6
  *  \author  Sebastian Scherer <basti@andrew.cmu.edu>
7
  *  \date    2011 October 25
8
  *  \details This program sends commands to a Mikrokopter rotorcraft via ROS
9
  */
10
11
#include "ros/ros.h"
12
#include "mikrokopter/Control.h"
13
#include <cstdlib>
14
15
int main(int argc, char **argv)
16
{
17
  ros::init(argc, argv, "mikrokopter_externctrl_client");
18
19
  ros::NodeHandle n;
20
  ros::Publisher pub = n.advertise<mikrokopter::Control>("/mikrokopter/req_set_control", 100);
21
  
22
  mikrokopter::Control req;
23
24
  req.digital[0] = 0;
25
  req.digital[1] = 0;
26
  req.remoteKey = 0;
27
  req.pitch = 0;
28
  req.roll = 0;
29
  req.yaw = 0;
30
  req.thrust = 40;
31
  req.height = 0;
32
  req.free = 0;
33
  req.frame = 7;
34
  req.config = 1;
35
  
36
  ros::Rate loop_rate(25);
37
  
38
  
39
  int maxPt = 30;
40
  int minPt = -30;
41
  int step = 2;
42
  int val = 30;
43
  
44
  while (ros::ok())
45
  {
46
47
    if (val >= maxPt)
48
      step = -1*step;
49
    if (val <= minPt)
50
      step = -1*step;
51
  
52
    val += step;
53
54
    std::cout << val << std::endl;
55
  
56
    req.frame++;
57
    req.roll = val;
58
59
    pub.publish(req);
60
61
    ros::spinOnce();
62
    loop_rate.sleep();
63
  }
64
65
  return 0;
66
}