Fawkes API  Fawkes Development Version
qa_player_setmotor.cpp
1 
2 /***************************************************************************
3  * qa_player_setmotor.cpp - Player QA App: set motor values
4  *
5  * Created: Tue Sep 30 23:40:57 2008
6  * Copyright 2006-2008 Tim Niemueller [www.niemueller.de]
7  *
8  ****************************************************************************/
9 
10 /* This program is free software; you can redistribute it and/or modify
11  * it under the terms of the GNU General Public License as published by
12  * the Free Software Foundation; either version 2 of the License, or
13  * (at your option) any later version.
14  *
15  * This program is distributed in the hope that it will be useful,
16  * but WITHOUT ANY WARRANTY; without even the implied warranty of
17  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
18  * GNU Library General Public License for more details.
19  *
20  * Read the full text in the LICENSE.GPL file in the doc directory.
21  */
22 
23 #include <blackboard/remote.h>
24 #include <interfaces/MotorInterface.h>
25 
26 #include <unistd.h>
27 #include <cstdio>
28 
29 using namespace fawkes;
30 
31 int
32 main(int argc, char **argv)
33 {
34  BlackBoard *bb = new RemoteBlackBoard("localhost", 1910);
35 
36  MotorInterface *motor = bb->open_for_reading<MotorInterface>("Player Motor");
37  motor->read();
38 
39  printf("Motor x=%f y=%f z=%f\n",
40  motor->odometry_position_x(), motor->odometry_position_y(),
41  motor->odometry_orientation());
42 
43  printf("Setting relative (2, 0, 0), this is (%f, %f, %f) global\n",
44  motor->odometry_position_x() + 2, motor->odometry_position_y(),
45  motor->odometry_orientation());
46 
48  motor->odometry_position_y(),
49  motor->odometry_orientation(),
50  1 /* sec */));
51 
52  bb->close(motor);
53 
54  delete bb;
55  return 0;
56 }
float odometry_position_x() const
Get odometry_position_x value.
Fawkes library namespace.
float odometry_orientation() const
Get odometry_orientation value.
float odometry_position_y() const
Get odometry_position_y value.
void read()
Read from BlackBoard into local copy.
Definition: interface.cpp:477
unsigned int msgq_enqueue(Message *message)
Enqueue message at end of queue.
Definition: interface.cpp:903
Remote BlackBoard.
Definition: remote.h:48
virtual Interface * open_for_reading(const char *interface_type, const char *identifier, const char *owner=NULL)=0
Open interface for reading.
MotorInterface Fawkes BlackBoard Interface.
The BlackBoard abstract class.
Definition: blackboard.h:48
GotoMessage Fawkes BlackBoard Interface Message.
virtual void close(Interface *interface)=0
Close interface.