kinematics-dynamics
CartesianControlServer.hpp
1 // -*- mode:C++; tab-width:4; c-basic-offset:4; indent-tabs-mode:nil -*-
2 
3 #ifndef __CARTESIAN_CONTROL_SERVER_HPP__
4 #define __CARTESIAN_CONTROL_SERVER_HPP__
5 
6 #include <vector>
7 
8 #include <yarp/os/Bottle.h>
9 #include <yarp/os/BufferedPort.h>
10 #include <yarp/os/PeriodicThread.h>
11 #include <yarp/os/RpcServer.h>
12 
13 #include <yarp/dev/Drivers.h>
14 #include <yarp/dev/PolyDriver.h>
15 #include <yarp/dev/WrapperSingle.h>
16 
17 #include "ICartesianControl.h"
18 #include "KinematicRepresentation.hpp"
19 
20 namespace roboticslab
21 {
22 
30 class RpcResponder;
31 class RpcTransformResponder;
32 class StreamResponder;
33 
38 class CartesianControlServer : public yarp::dev::DeviceDriver,
39  public yarp::dev::WrapperSingle,
40  public yarp::os::PeriodicThread
41 {
42 public:
43  CartesianControlServer() : yarp::os::PeriodicThread(1.0)
44  {}
45 
46  // -------- DeviceDriver declarations. Implementation in IDeviceImpl.cpp --------
47  bool open(yarp::os::Searchable & config) override;
48  bool close() override;
49 
50  // -------- IWrapper declarations. Implementation in IWrapperImpl.cpp --------
51  bool attach(yarp::dev::PolyDriver * poly) override;
52  bool detach() override;
53 
54  // -------- PeriodicThread declarations. Implementation in PeriodicThreadImpl.cpp --------
55  void run() override;
56 
57 protected:
58  bool configureHandle();
59 
60  yarp::dev::PolyDriver cartesianControlDevice;
61 
62  yarp::os::RpcServer rpcServer, rpcTransformServer;
63  yarp::os::BufferedPort<yarp::os::Bottle> fkOutPort, commandPort;
64 
65  ICartesianControl * iCartesianControl {nullptr};
66 
67  RpcResponder * rpcResponder {nullptr};
68  RpcResponder * rpcTransformResponder {nullptr};
69  StreamResponder * streamResponder {nullptr};
70 };
71 
76 class RpcResponder : public yarp::dev::DeviceResponder
77 {
78 public:
79  RpcResponder()
80  {
81  // shadows DeviceResponder::makeUsage(), which was already called by the base constructor
82  makeUsage();
83  }
84 
85  void setHandle(ICartesianControl * _iCartesianControl)
86  { iCartesianControl = _iCartesianControl; }
87 
88  bool respond(const yarp::os::Bottle & in, yarp::os::Bottle & out) override;
89  void makeUsage();
90 
91 protected:
92  virtual bool transformIncomingData(std::vector<double> & vin)
93  { return true; }
94 
95  virtual bool transformOutgoingData(std::vector<double> & vout)
96  { return true; }
97 
98 private:
99  using RunnableFun = bool (ICartesianControl::*)();
100  using ConsumerFun = bool (ICartesianControl::*)(const std::vector<double> &);
101  using FunctionFun = bool (ICartesianControl::*)(const std::vector<double> &, std::vector<double> &);
102 
103  bool handleStatMsg(const yarp::os::Bottle & in, yarp::os::Bottle & out);
104  bool handleWaitMsg(const yarp::os::Bottle & in, yarp::os::Bottle & out);
105  bool handleActMsg(const yarp::os::Bottle & in, yarp::os::Bottle & out);
106 
107  bool handleRunnableCmdMsg(const yarp::os::Bottle & in, yarp::os::Bottle & out, RunnableFun cmd);
108  bool handleConsumerCmdMsg(const yarp::os::Bottle & in, yarp::os::Bottle & out, ConsumerFun cmd);
109  bool handleFunctionCmdMsg(const yarp::os::Bottle & in, yarp::os::Bottle & out, FunctionFun cmd);
110 
111  bool handleParameterSetter(const yarp::os::Bottle & in, yarp::os::Bottle & out);
112  bool handleParameterGetter(const yarp::os::Bottle & in, yarp::os::Bottle & out);
113 
114  bool handleParameterSetterGroup(const yarp::os::Bottle & in, yarp::os::Bottle & out);
115  bool handleParameterGetterGroup(const yarp::os::Bottle & in, yarp::os::Bottle & out);
116 
117  ICartesianControl * iCartesianControl;
118 };
119 
125 {
126 public:
130  : coord(coord),
131  orient(orient),
132  units(units)
133  {}
134 
135 private:
136  bool transformIncomingData(std::vector<double> & vin) override;
137  bool transformOutgoingData(std::vector<double> & vout) override;
138 
142 };
143 
148 class StreamResponder : public yarp::os::TypedReaderCallback<yarp::os::Bottle>
149 {
150 public:
151  void setHandle(ICartesianControl * _iCartesianControl)
152  { iCartesianControl = _iCartesianControl;}
153 
154  void onRead(yarp::os::Bottle & b) override;
155 
156 private:
157  using ConsumerFun = void (ICartesianControl::*)(const std::vector<double> &);
158  using BiConsumerFun = void (ICartesianControl::*)(const std::vector<double> &, double);
159 
160  void handleConsumerCmdMsg(const yarp::os::Bottle & in, ConsumerFun cmd);
161  void handleBiConsumerCmdMsg(const yarp::os::Bottle & in, BiConsumerFun cmd);
162 
163  ICartesianControl * iCartesianControl {nullptr};
164 };
165 
166 } // namespace roboticslab
167 
168 #endif // __CARTESIAN_CONTROL_SERVER_HPP__
Contains roboticslab::ICartesianControl and related vocabs.
The CartesianControlServer class implements ICartesianControl server side.
Definition: CartesianControlServer.hpp:41
Abstract base class for a cartesian controller.
Definition: ICartesianControl.h:146
Responds to RPC command messages.
Definition: CartesianControlServer.hpp:77
Responds to RPC command messages, transforms incoming data.
Definition: CartesianControlServer.hpp:125
Responds to streaming command messages.
Definition: CartesianControlServer.hpp:149
coordinate_system
Lists available translational representations.
Definition: KinematicRepresentation.hpp:27
orientation_system
Lists available rotational representations.
Definition: KinematicRepresentation.hpp:36
angular_units
Lists recognized angular units.
Definition: KinematicRepresentation.hpp:48
The main, catch-all namespace for Robotics Lab UC3M.
Definition: groups.dox:6