-
Notifications
You must be signed in to change notification settings - Fork 48
/
ControlBoard.cc
245 lines (202 loc) · 9.03 KB
/
ControlBoard.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
/*
* Copyright (C) 2013-2015 Fondazione Istituto Italiano di Tecnologia RBCS & iCub Facility & ADVR
* Authors: see AUTHORS file.
* CopyPolicy: Released under the terms of the LGPLv2.1 or any later version, see LGPL.TXT or LGPL3.TXT
*/
#include "ControlBoard.hh"
#include "ControlBoardDriver.h"
#include <GazeboYarpPlugins/common.h>
#include <GazeboYarpPlugins/Handler.hh>
#include <GazeboYarpPlugins/ConfHelpers.hh>
#include <gazebo/physics/Model.hh>
#include <yarp/dev/IMultipleWrapper.h>
#include <yarp/os/Network.h>
#include <yarp/os/Log.h>
#include <yarp/os/LogStream.h>
using namespace std;
namespace gazebo
{
GZ_REGISTER_MODEL_PLUGIN(GazeboYarpControlBoard)
GazeboYarpControlBoard::GazeboYarpControlBoard() : m_iWrap(nullptr),
m_iVirtAnalogSensorWrap(nullptr)
{}
GazeboYarpControlBoard::~GazeboYarpControlBoard()
{
if (m_iWrap) {
m_iWrap->detachAll();
m_iWrap = nullptr;
}
if (m_wrapper.isValid()) {
m_wrapper.close();
}
if (m_iVirtAnalogSensorWrap)
{
m_iVirtAnalogSensorWrap->detachAll();
m_iVirtAnalogSensorWrap = nullptr;
}
if (m_virtAnalogSensorWrapper.isValid())
{
m_virtAnalogSensorWrapper.close();
}
for (int n = 0; n < m_controlBoards.size(); n++) {
std::string scopedDeviceName = m_robotName + "::" + m_controlBoards[n]->key.c_str();
GazeboYarpPlugins::Handler::getHandler()->removeDevice(scopedDeviceName);
}
GazeboYarpPlugins::Handler::getHandler()->removeRobot(m_robotName);
yarp::os::Network::fini();
}
/**
* Saves the gazebo pointer, creates the device driver
*/
void GazeboYarpControlBoard::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
{
yarp::os::Network::init();
if (!yarp::os::Network::checkNetwork(GazeboYarpPlugins::yarpNetworkInitializationTimeout)) {
yError() << "GazeboYarpControlBoard : yarp network does not seem to be available, is the yarpserver running?";
return;
}
if (!_parent) {
gzerr << "GazeboYarpControlBoard plugin requires a parent.\n";
return;
}
m_robotName = _parent->GetScopedName();
GazeboYarpPlugins::Handler::getHandler()->setRobot(get_pointer(_parent));
// Add the gazebo_controlboard device driver to the factory.
yarp::dev::Drivers::factory().add(new yarp::dev::DriverCreatorOf<yarp::dev::GazeboYarpControlBoardDriver>("gazebo_controlboard", "controlboardwrapper2", "GazeboYarpControlBoardDriver"));
//Getting .ini configuration file from sdf
bool configuration_loaded = GazeboYarpPlugins::loadConfigModelPlugin(_parent, _sdf, m_parameters);
if (!configuration_loaded)
{
yError() << "GazeboYarpControlBoard : File .ini not found, load failed." ;
return;
}
yarp::os::Bottle wrapper_group = m_parameters.findGroup("WRAPPER");
if(wrapper_group.isNull())
{
yError("GazeboYarpControlBoard : [WRAPPER] group not found in config file\n");
return;
}
if(m_parameters.check("ROS"))
{
std::string ROS;
ROS = std::string ("(") + m_parameters.findGroup("ROS").toString() + std::string (")");
wrapper_group.append(yarp::os::Bottle(ROS));
}
m_wrapper.open(wrapper_group);
if (!m_wrapper.isValid()) {
yError("GazeboYarpControlBoard : wrapper did not open, load failed.");
m_wrapper.close();
return;
}
if (!m_wrapper.view(m_iWrap)) {
yError("GazeboYarpControlBoard : wrapper interface not found, load failed.");
return;
}
yarp::os::Bottle *netList = wrapper_group.find("networks").asList();
if (netList->isNull()) {
yError("GazeboYarpControlBoard : net list to attach to was not found, load failed.");
m_wrapper.close();
return;
}
yarp::os::Bottle driver_group;
yarp::os::Bottle virt_group;
m_useVirtAnalogSensor = m_parameters.check("useVirtualAnalogSensor", yarp::os::Value(false)).asBool();
if (m_useVirtAnalogSensor)
{
virt_group = m_parameters.findGroup("VIRTUAL_ANALOG_SERVER");
if (virt_group.isNull())
{
yError("GazeboYarpControlBoard : [VIRTUAL_ANALOG_SERVER] group not found in config file\n");
return;
}
yarp::os::Bottle& robotName_config = virt_group.addList();
robotName_config.addString("robotName");
robotName_config.addString(m_robotName.c_str());
std::string networks = std::string("(") + wrapper_group.findGroup("networks").toString() + std::string(")");
virt_group.append(yarp::os::Bottle(networks));
}
for (int n = 0; n < netList->size(); n++)
{
yarp::dev::PolyDriverDescriptor newPoly;
newPoly.key = netList->get(n).asString();
// initially deal with virtual analog stuff
if (m_useVirtAnalogSensor)
{
std::string net = std::string("(") + wrapper_group.findGroup(newPoly.key.c_str()).toString() + std::string(")");
virt_group.append(yarp::os::Bottle(net));
}
std::string scopedDeviceName = m_robotName + "::" + newPoly.key.c_str();
newPoly.poly = GazeboYarpPlugins::Handler::getHandler()->getDevice(scopedDeviceName);
if( newPoly.poly != NULL)
{
// device already exists, use it, setting it againg to increment the usage counter.
yWarning("GazeboYarpControlBoard : controlBoard %s already opened.", newPoly.key.c_str());
}
else
{
driver_group = m_parameters.findGroup(newPoly.key.c_str());
if (driver_group.isNull()) {
yError("GazeboYarpControlBoard : [%s] group not found in config file. Closing wrapper.", newPoly.key.c_str());
m_wrapper.close();
return;
}
m_parameters.put("name", newPoly.key.c_str());
m_parameters.fromString(driver_group.toString(), false);
m_parameters.put("robotScopedName", m_robotName);
if (_sdf->HasElement("initialConfiguration")) {
//yDebug()<<"Found initial Configuration: ";
std::string configuration_s = _sdf->Get<std::string>("initialConfiguration");
m_parameters.put("initialConfiguration", configuration_s.c_str());
//yDebug()<<configuration_s;
}
newPoly.poly = new yarp::dev::PolyDriver;
if(! newPoly.poly->open(m_parameters) || ! newPoly.poly->isValid())
{
yError() << "GazeboYarpControlBoard : controlBoard <" << newPoly.key << "> did not open.";
for(int idx=0; idx<m_controlBoards.size(); idx++)
{
m_controlBoards[idx]->poly->close();
}
m_wrapper.close();
return;
}
}
GazeboYarpPlugins::Handler::getHandler()->setDevice(scopedDeviceName, newPoly.poly);
m_controlBoards.push(newPoly);
}
if (m_useVirtAnalogSensor)
{
m_virtAnalogSensorWrapper.open(virt_group);
if (!m_virtAnalogSensorWrapper.isValid())
{
yError("GazeboYarpControlBoard : Virtual analog sensor wrapper did not open, load failed.");
m_virtAnalogSensorWrapper.close();
return;
}
if (!m_virtAnalogSensorWrapper.view(m_iVirtAnalogSensorWrap))
{
yError("GazeboYarpControlBoard : Could not view the IVirtualAnalogSensor interface");
return;
}
if (!m_iVirtAnalogSensorWrap->attachAll(m_controlBoards))
{
yError("GazeboYarpControlBoard : Could not attach VirtualAnalogSensor interface to controlboards");
return;
}
}
if (!m_iWrap || !m_iWrap->attachAll(m_controlBoards))
{
yError("GazeboYarpControlBoard : error while attaching wrapper to device.");
m_wrapper.close();
if (m_useVirtAnalogSensor)
{
m_virtAnalogSensorWrapper.close();
}
for (int n = 0; n < netList->size(); n++) {
std::string scopedDeviceName = m_robotName + "::" + m_controlBoards[n]->key.c_str();
GazeboYarpPlugins::Handler::getHandler()->removeDevice(scopedDeviceName);
}
return;
}
}
}