|
YARP
Yet Another Robot Platform
|
|
Go to the documentation of this file.
42 m_remote_name.clear();
47 if (m_local_name ==
"")
49 yCError(LOCALIZATION2DCLIENT,
"open() error you have to provide a valid 'local' param");
53 if (m_remote_name ==
"")
55 yCError(LOCALIZATION2DCLIENT,
"open() error you have to provide valid 'remote' param");
62 remote_streaming_name,
65 local_rpc = m_local_name +
"/localization/rpc";
66 remote_rpc = m_remote_name +
"/rpc";
67 remote_streaming_name = m_remote_name +
"/stream:o";
68 local_streaming_name = m_local_name +
"/stream:i";
70 if (!m_rpc_port_localization_server.open(local_rpc))
72 yCError(LOCALIZATION2DCLIENT,
"open() error could not open rpc port %s, check network", local_rpc.c_str());
87 ok = Network::connect(local_rpc, remote_rpc);
90 yCError(LOCALIZATION2DCLIENT,
"open() error could not connect to %s", remote_rpc.c_str());
109 bool ret = m_rpc_port_localization_server.write(b, resp);
114 yCError(LOCALIZATION2DCLIENT) <<
"setInitialPose() received error from localization server";
120 yCError(LOCALIZATION2DCLIENT) <<
"setInitialPose() error on writing on rpc port";
128 if (cov.
rows() != 3 || cov.
cols() != 3)
130 yCError(LOCALIZATION2DCLIENT) <<
"Covariance matrix is expected to have size (3,3)";
143 for (
size_t i = 0; i < 3; i++) {
for (
size_t j = 0; j < 3; j++) { mc.
addFloat64(cov[i][j]); }}
145 bool ret = m_rpc_port_localization_server.write(b, resp);
150 yCError(LOCALIZATION2DCLIENT) <<
"setInitialPose() received error from localization server";
156 yCError(LOCALIZATION2DCLIENT) <<
"setInitialPose() error on writing on rpc port";
164 yCError(LOCALIZATION2DCLIENT) <<
"getEstimatedOdometry is not yet implemented";
176 bool ret = m_rpc_port_localization_server.write(b, resp);
181 yCError(LOCALIZATION2DCLIENT) <<
"getCurrentPosition() received error from localization server";
195 yCError(LOCALIZATION2DCLIENT) <<
"getCurrentPosition() error on writing on rpc port";
209 bool ret = m_rpc_port_localization_server.write(b, resp);
214 yCError(LOCALIZATION2DCLIENT) <<
"getCurrentPosition() received error from localization server";
219 if (cov.
rows() != 3 || cov.
cols() != 3)
221 yCDebug(LOCALIZATION2DCLIENT) <<
"Performance warning: covariance matrix is not (3,3), resizing...";
229 if (mc ==
nullptr)
return false;
230 for (
size_t i = 0; i < 3; i++) {
for (
size_t j = 0; j < 3; j++) { cov[i][j] = mc->
get(i*3+j).
asFloat64(); } }
236 yCError(LOCALIZATION2DCLIENT) <<
"getCurrentPosition() error on writing on rpc port";
250 bool ret = m_rpc_port_localization_server.write(b, resp);
255 yCError(LOCALIZATION2DCLIENT) <<
"getEstimatedPoses() received error from localization server";
262 for (
int i = 0; i < nposes; i++)
276 yCError(LOCALIZATION2DCLIENT) <<
"getEstimatedPoses() parsing error";
279 poses.push_back(loc);
286 yCError(LOCALIZATION2DCLIENT) <<
"getEstimatedPoses() error on writing on rpc port";
300 bool ret = m_rpc_port_localization_server.write(b, resp);
305 yCError(LOCALIZATION2DCLIENT) <<
"getLocalizationStatus() received error from localization server";
316 yCError(LOCALIZATION2DCLIENT) <<
"getLocalizationStatus() error on writing on rpc port";
330 bool ret = m_rpc_port_localization_server.write(b, resp);
335 yCError(LOCALIZATION2DCLIENT) <<
"startLocalizationService() received error from navigation server";
341 yCError(LOCALIZATION2DCLIENT) <<
"startLocalizationService() error on writing on rpc port";
355 bool ret = m_rpc_port_localization_server.write(b, resp);
360 yCError(LOCALIZATION2DCLIENT) <<
"stopLocalizationService() received error from navigation server";
366 yCError(LOCALIZATION2DCLIENT) <<
"stopLocalizationService() error on writing on rpc port";
374 m_rpc_port_localization_server.close();
A simple collection of objects that can be described and transmitted in a portable way.
virtual std::int32_t asVocab() const
Get vocabulary identifier as an integer.
bool startLocalizationService() override
Starts the localization service.
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_CURRENT_POS
A base class for nested structures that can be searched.
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_LOCALIZER_POSES
bool getEstimatedOdometry(yarp::dev::OdometryData &odom) override
Gets the estimated odometry the robot, including its velocity expressed in the world and in the local...
size_type size() const
Gets the number of elements in the bottle.
bool getEstimatedPoses(std::vector< yarp::dev::Nav2D::Map2DLocation > &poses) override
Gets a set of pose estimates computed by the localization algorithm.
bool getCurrentPosition(yarp::dev::Nav2D::Map2DLocation &loc) override
Gets the current position of the robot w.r.t world reference frame.
#define YARP_LOG_COMPONENT(name,...)
size_t rows() const
Return number of rows.
void addFloat64(yarp::conf::float64_t x)
Places a 64-bit floating point number in the bottle, at the end of the list.
An interface for the device drivers.
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
Bottle & addList()
Places an empty nested list in the bottle, at the end of the list.
virtual std::string asString() const
Get string value.
bool stopLocalizationService() override
Stops the localization service.
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_LOCALIZER_STATUS
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
constexpr yarp::conf::vocab32_t VOCAB_NAV_LOCALIZATION_START
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
void addString(const char *str)
Places a string in the bottle, at the end of the list.
constexpr yarp::conf::vocab32_t VOCAB_NAV_SET_INITIAL_POSCOV
size_t cols() const
Return number of columns.
void addVocab(int x)
Places a vocabulary item in the bottle, at the end of the list.
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_CURRENT_POSCOV
void resize(size_t r, size_t c)
Resize the matrix, if matrix is not empty preserve old content.
#define yCError(component,...)
virtual std::int32_t asInt32() const
Get 32-bit integer value.
bool getLocalizationStatus(yarp::dev::Nav2D::LocalizationStatusEnum &status) override
Gets the current status of the localization task.
bool close() override
Close the DeviceDriver.
An interface to the operating system, including Port based communication.
#define yCDebug(component,...)
virtual Bottle * asList() const
Get list value.
constexpr yarp::conf::vocab32_t VOCAB_NAV_LOCALIZATION_STOP
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
constexpr yarp::conf::vocab32_t VOCAB_OK
constexpr yarp::conf::vocab32_t VOCAB_INAVIGATION
constexpr yarp::conf::vocab32_t VOCAB_NAV_SET_INITIAL_POS
bool setInitialPose(const yarp::dev::Nav2D::Map2DLocation &loc) override
Sets the initial pose for the localization algorithm which estimates the current position of the robo...