|
YARP
Yet Another Robot Platform
|
|
Go to the documentation of this file.
43 #define DEFAULT_THREAD_PERIOD 0.01
46 #define M_PI 3.14159265358979323846
69 if (device2attach.
size() != 1)
71 yCError(LOCALIZATION2DSERVER,
"Cannot attach more than one device");
84 yCError(LOCALIZATION2DSERVER,
"Subdevice passed to attach method is invalid");
101 yCWarning(LOCALIZATION2DSERVER) <<
"Localization data not yet available during server initialization";
104 PeriodicThread::setPeriod(
m_period);
105 return PeriodicThread::start();
110 if (PeriodicThread::isRunning())
112 PeriodicThread::stop();
122 yCDebug(LOCALIZATION2DSERVER) <<
"Configuration: \n" << config.
toString().c_str();
124 if (config.
check(
"GENERAL") ==
false)
126 yCWarning(LOCALIZATION2DSERVER) <<
"Missing GENERAL group, assuming default options";
130 if (!general_group.
check(
"period"))
141 if (!general_group.
check(
"retrieve_position_periodically"))
143 yCInfo(LOCALIZATION2DSERVER) <<
"Missing 'retrieve_position_periodically' parameter. Using default value: true. Period:" <<
m_period ;
150 {
yCInfo(LOCALIZATION2DSERVER) <<
"retrieve_position_periodically requested, Period:" <<
m_period; }
152 {
yCInfo(LOCALIZATION2DSERVER) <<
"retrieve_position_periodically NOT requested. Localization data obtained asynchronously."; }
157 if (!general_group.
check(
"name"))
159 yCInfo(LOCALIZATION2DSERVER) <<
"Missing 'name' parameter. Using default value: /localizationServer";
164 if (
m_local_name.c_str()[0] !=
'/') {
yCError(LOCALIZATION2DSERVER) <<
"Missing '/' in name parameter" ;
return false; }
172 if (config.
check(
"subdevice"))
181 yCError(LOCALIZATION2DSERVER) <<
"Failed to open subdevice.. check params";
188 yCError(LOCALIZATION2DSERVER) <<
"Failed to open subdevice.. check params";
194 yCInfo(LOCALIZATION2DSERVER) <<
"Waiting for device to attach";
200 yCError(LOCALIZATION2DSERVER) <<
"Error initializing YARP ports";
206 yCError(LOCALIZATION2DSERVER) <<
"Error initializing ROS system";
215 if (params.
check(
"ROS"))
218 if (ros_group.
check(
"publish_tf"))
222 if (ros_group.
check(
"publish_odom"))
227 if (!ros_group.
check(
"parent_frame_id"))
229 yCError(LOCALIZATION2DSERVER) <<
"Missing 'parent_frame_id' parameter";
236 if (!ros_group.
check(
"child_frame_id"))
238 yCError(LOCALIZATION2DSERVER) <<
"Missing 'child_frame_id' parameter";
249 yCInfo(LOCALIZATION2DSERVER) <<
"ROS initialization not requested";
259 yCError(LOCALIZATION2DSERVER) <<
"Opening " <<
m_local_name <<
" Node, check your yarp-ROS network configuration";
266 yCError(LOCALIZATION2DSERVER) <<
"Unable to publish data on" << ros_odom_topic <<
"topic";
271 yCError(LOCALIZATION2DSERVER) <<
"Unable to publish data on /tf topic";
273 yCInfo(LOCALIZATION2DSERVER) <<
"ROS initialized";
304 yCTrace(LOCALIZATION2DSERVER,
"Close");
305 if (PeriodicThread::isRunning())
307 PeriodicThread::stop();
327 yCDebug(LOCALIZATION2DSERVER) <<
"Execution terminated";
335 bool ok = command.
read(connection);
336 if (!ok)
return false;
388 for (
size_t i = 0; i < 3; i++) {
for (
size_t j = 0; j < 3; j++) { mc.
addFloat64(cov[i][j]); } }
399 if (mc!=
nullptr && mc->
size() == 9)
401 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(); } }
439 std::vector<Map2DLocation> poses;
443 for (
size_t i=0; i<poses.size(); i++)
459 yCError(LOCALIZATION2DSERVER) <<
"Invalid vocab received";
466 reply.
addString(
"Available commands are:");
468 reply.
addString(
"initLoc <map_name> <x> <y> <angle in degrees>");
474 std::string s = std::string(
"Current Location is: ") + curr_loc.
toString();
485 std::string s = std::string(
"Localization initialized to: ") + init_loc.
toString();
490 yCError(LOCALIZATION2DSERVER) <<
"Invalid command type";
495 if (returnToSender !=
nullptr)
497 reply.
write(*returnToSender);
508 yCInfo(LOCALIZATION2DSERVER) <<
"Running";
517 yCError(LOCALIZATION2DSERVER) <<
"getLocalizationStatus() failed";
528 yCError(LOCALIZATION2DSERVER) <<
"getCurrentPosition() failed";
546 yCWarning(LOCALIZATION2DSERVER,
"The system is not properly localized!");
550 if (1) publish_odometry_on_yarp_port();
551 if (1) publish_2DLocation_on_yarp_port();
557 void Localization2DServer::publish_odometry_on_yarp_port()
570 void Localization2DServer::publish_2DLocation_on_yarp_port()
582 temp_loc.
x = std::nan(
"");
583 temp_loc.
y = std::nan(
"");
584 temp_loc.
theta = std::nan(
"");
594 void Localization2DServer::publish_odometry_on_TF_topic()
603 double cosYaw = cos(halfYaw);
604 double sinYaw = sin(halfYaw);
624 void Localization2DServer::publish_odometry_on_ROS_topic()
void close() override
Stop port activity.
A simple collection of objects that can be described and transmitted in a portable way.
void close() override
Stop port activity.
virtual std::int32_t asVocab() const
Get vocabulary identifier as an integer.
yarp::os::BufferedPort< yarp::dev::OdometryData > m_odometryPort
yarp::dev::Nav2D::Map2DLocation m_current_position
void put(const std::string &key, const std::string &value)
Associate the given key with the given string.
void clear()
Empties the bottle of any objects it contains.
double base_vel_theta
angular velocity of the robot [deg/s] expressed in the robot reference frame
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
void fromRotationMatrix(const yarp::sig::Matrix &R)
Converts a rotation matrix to a quaternion.
size_type size() const
Gets the number of elements in the bottle.
contains the definition of a Vector type
virtual bool detachAll() override
Detach the object (you must have first called attach).
yarp::dev::OdometryData m_current_odometry
yarp::rosmsg::geometry_msgs::Twist twist
virtual Bottle & findGroup(const std::string &key) const =0
Gets a list corresponding to a given keyword.
yarp::rosmsg::geometry_msgs::Point position
@ localization_status_not_yet_localized
#define yCWarning(component,...)
double base_vel_y
velocity of the robot [m/s] expressed in the robot reference frame
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
std::string toString() const
Returns text representation of the location.
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
yarp::dev::Nav2D::LocalizationStatusEnum m_current_status
bool isValid() const
Check if device is valid.
#define YARP_LOG_COMPONENT(name,...)
std::vector< yarp::rosmsg::geometry_msgs::TransformStamped > transforms
bool m_getdata_using_periodic_thread
int getOutputCount() override
Determine how many output connections this port has.
yarp::rosmsg::geometry_msgs::Pose pose
void interrupt() override
Interrupt any current reads or writes attached to the port.
bool setEnvelope(PortWriter &envelope) override
Set an envelope (e.g., a timestamp) to the next message which will be sent.
bool view(T *&x)
Get an interface to the device driver.
virtual bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
bool m_ros_publish_odometry_on_topic
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
yarp::rosmsg::geometry_msgs::Quaternion orientation
#define DEFAULT_THREAD_PERIOD
define control board standard interfaces
void addFloat64(yarp::conf::float64_t x)
Places a 64-bit floating point number in the bottle, at the end of the list.
bool open(const std::string &txt)
Construct and configure a device by its common name.
yarp::dev::Nav2D::ILocalization2D * iLoc
Value & find(const std::string &key) const override
Gets a value corresponding to a given keyword.
double now()
Return the current time in seconds, relative to an arbitrary starting point.
An interface for the device drivers.
double base_vel_x
velocity of the robot [m/s] expressed in the robot reference frame
yarp::os::Node * m_ros_node
yarp::sig::Matrix rpy2dcm(const yarp::sig::Vector &rpy)
Converts roll-pitch-yaw angles in the corresponding dcm (direction cosine matrix) rotation matrix (de...
virtual void run() override
Loop function.
std::string m_rpcPortName
void push(PolyDriver *p, const char *k)
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::BufferedPort::write.
yarp::os::Publisher< yarp::rosmsg::nav_msgs::Odometry > m_odometry_publisher
bool check(const std::string &key) const override
Check if there exists a property of the given name.
int getOutputCount() override
Determine how many output connections this port has.
virtual bool getEstimatedOdometry(yarp::dev::OdometryData &odom)=0
Gets the estimated odometry the robot, including its velocity expressed in the world and in the local...
virtual bool isString() const
Checks if value is a string.
yarp::dev::PolyDriver pLoc
std::string m_fixed_frame
@ localization_status_localized_ok
bool topic(const std::string &name)
Set topic to publish to.
virtual bool startLocalizationService()=0
Starts the localization service.
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
std::string m_odometryPortName
Bottle & addList()
Places an empty nested list in the bottle, at the end of the list.
void write(bool forceStrict=false)
Write the current object being returned by Publisher::prepare.
bool write(ConnectionWriter &writer) const override
Output a representation of the bottle to a network connection.
An interface for writing to a network connection.
yarp::rosmsg::geometry_msgs::Vector3 linear
std::string m_2DLocationPortName
double odom_theta
orientation the robot [deg], expressed in the world reference frame
std::string m_robot_frame
yarp::os::Stamp m_loc_stamp
double getTime() const
Get the time stamp.
bool initialize_ROS(yarp::os::Searchable &config)
virtual bool asBool() const
Get boolean value.
virtual std::string asString() const
Get string value.
A container for a device driver.
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_LOCALIZER_STATUS
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
constexpr yarp::conf::vocab32_t VOCAB_NAV_LOCALIZATION_START
yarp::rosmsg::geometry_msgs::PoseWithCovariance pose
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
void addInt32(std::int32_t x)
Places a 32-bit integer in the bottle, at the end of the list.
NetInt32 encode(const std::string &str)
Convert a string into a vocabulary identifier.
int getCount() const
Get the sequence number.
std::string child_frame_id
virtual ConnectionWriter * getWriter()=0
Gets a way to reply to the message, if possible.
yarp::rosmsg::geometry_msgs::Vector3 angular
void addString(const char *str)
Places a string in the bottle, at the end of the list.
yarp::rosmsg::geometry_msgs::TwistWithCovariance twist
void setReader(PortReader &reader) override
Set an external reader for port data.
constexpr yarp::conf::vocab32_t VOCAB_NAV_SET_INITIAL_POSCOV
An abstraction for a periodic thread.
yarp::os::Stamp m_odom_stamp
Port & asPort() override
Get the concrete Port being used for communication.
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
virtual bool stopLocalizationService()=0
Stops the localization service.
constexpr yarp::conf::vocab32_t VOCAB_ERR
virtual bool setInitialPose(const yarp::dev::Nav2D::Map2DLocation &loc)=0
Sets the initial pose for the localization algorithm which estimates the current position of the robo...
An interface for reading from a network connection.
virtual bool open(yarp::os::Searchable &prop) override
Open the DeviceDriver.
#define yCError(component,...)
void update()
Set the timestamp to the current time, and increment the sequence number (wrapping to 0 if the sequen...
void write(bool forceStrict=false)
Write the current object being returned by BufferedPort::prepare.
#define yCInfo(component,...)
virtual bool getLocalizationStatus(LocalizationStatusEnum &status)=0
Gets the current status of the localization task.
An interface to the operating system, including Port based communication.
#define yCDebug(component,...)
yarp::rosmsg::std_msgs::Header header
double odom_y
position of the robot [m], expressed in the world reference frame
void close() override
Stop port activity.
bool read(ConnectionReader &reader) override
Set the bottle's value based on input from a network connection.
double odom_x
position of the robot [m], expressed in the world reference frame
void interrupt() override
Interrupt any current reads or writes attached to the port.
virtual Bottle * asList() const
Get list value.
#define yCTrace(component,...)
yarp::os::BufferedPort< yarp::dev::Nav2D::Map2DLocation > m_2DLocationPort
virtual bool attachAll(const yarp::dev::PolyDriverList &l) override
Attach to a list of objects.
virtual bool getCurrentPosition(yarp::dev::Nav2D::Map2DLocation &loc)=0
Gets the current position of the robot w.r.t world reference frame.
constexpr yarp::conf::vocab32_t VOCAB_NAV_LOCALIZATION_STOP
std::string m_parent_frame_id
yarp::os::Publisher< yarp::rosmsg::tf2_msgs::TFMessage > m_tf_publisher
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
virtual bool getEstimatedPoses(std::vector< yarp::dev::Nav2D::Map2DLocation > &poses)=0
Gets a set of pose estimates computed by the localization algorithm.
constexpr yarp::conf::vocab32_t VOCAB_OK
constexpr yarp::conf::vocab32_t VOCAB_INAVIGATION
virtual bool isVocab() const
Checks if value is a vocabulary identifier.
constexpr yarp::conf::vocab32_t VOCAB_NAV_SET_INITIAL_POS
A class for storing options and configuration information.
bool m_ros_publish_odometry_on_tf
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::Publisher::write.
std::string m_child_frame_id
bool initialize_YARP(yarp::os::Searchable &config)
virtual bool close() override
Close the DeviceDriver.