29 #define DEFAULT_THREAD_PERIOD 0.01
32 #define M_PI 3.14159265358979323846
55 if (device2attach.
size() != 1)
57 yCError(LOCALIZATION2DSERVER,
"Cannot attach more than one device");
70 yCError(LOCALIZATION2DSERVER,
"Subdevice passed to attach method is invalid");
87 yCWarning(LOCALIZATION2DSERVER) <<
"Localization data not yet available during server initialization";
91 return PeriodicThread::start();
96 if (PeriodicThread::isRunning())
98 PeriodicThread::stop();
106 yCWarning(LOCALIZATION2DSERVER) <<
"The 'localization2DServer' device is deprecated in favour of 'localization2D_nws_yarp'.";
107 yCWarning(LOCALIZATION2DSERVER) <<
"The old device is no longer supported, and it will be deprecated in YARP 3.7 and removed in YARP 4.";
108 yCWarning(LOCALIZATION2DSERVER) <<
"Please update your scripts.";
112 yCDebug(LOCALIZATION2DSERVER) <<
"Configuration: \n" << config.
toString().c_str();
114 if (config.
check(
"GENERAL") ==
false)
116 yCWarning(LOCALIZATION2DSERVER) <<
"Missing GENERAL group, assuming default options";
120 if (!general_group.
check(
"period"))
131 if (!general_group.
check(
"retrieve_position_periodically"))
133 yCInfo(LOCALIZATION2DSERVER) <<
"Missing 'retrieve_position_periodically' parameter. Using default value: true. Period:" <<
m_period ;
140 {
yCInfo(LOCALIZATION2DSERVER) <<
"retrieve_position_periodically requested, Period:" <<
m_period; }
142 {
yCInfo(LOCALIZATION2DSERVER) <<
"retrieve_position_periodically NOT requested. Localization data obtained asynchronously."; }
147 if (!general_group.
check(
"name"))
149 yCInfo(LOCALIZATION2DSERVER) <<
"Missing 'name' parameter. Using default value: /localizationServer";
154 if (
m_local_name.c_str()[0] !=
'/') {
yCError(LOCALIZATION2DSERVER) <<
"Missing '/' in name parameter" ;
return false; }
162 if (config.
check(
"subdevice"))
171 yCError(LOCALIZATION2DSERVER) <<
"Failed to open subdevice.. check params";
178 yCError(LOCALIZATION2DSERVER) <<
"Failed to open subdevice.. check params";
184 yCInfo(LOCALIZATION2DSERVER) <<
"Waiting for device to attach";
190 yCError(LOCALIZATION2DSERVER) <<
"Error initializing YARP ports";
196 yCError(LOCALIZATION2DSERVER) <<
"Error initializing ROS system";
205 if (params.
check(
"ROS"))
208 if (ros_group.
check(
"publish_tf"))
212 if (ros_group.
check(
"publish_odom"))
217 if (!ros_group.
check(
"parent_frame_id"))
219 yCError(LOCALIZATION2DSERVER) <<
"Missing 'parent_frame_id' parameter";
226 if (!ros_group.
check(
"child_frame_id"))
228 yCError(LOCALIZATION2DSERVER) <<
"Missing 'child_frame_id' parameter";
239 yCInfo(LOCALIZATION2DSERVER) <<
"ROS initialization not requested";
249 yCError(LOCALIZATION2DSERVER) <<
"Opening " <<
m_local_name <<
" Node, check your yarp-ROS network configuration";
252 std::string ros_odom_topic =
m_local_name + std::string(
"/odom");
256 yCError(LOCALIZATION2DSERVER) <<
"Unable to publish data on" << ros_odom_topic <<
"topic";
261 yCError(LOCALIZATION2DSERVER) <<
"Unable to publish data on /tf topic";
263 yCInfo(LOCALIZATION2DSERVER) <<
"ROS initialized";
294 yCTrace(LOCALIZATION2DSERVER,
"Close");
295 if (PeriodicThread::isRunning())
297 PeriodicThread::stop();
317 yCDebug(LOCALIZATION2DSERVER) <<
"Execution terminated";
325 bool ok = command.
read(connection);
413 for (
size_t i = 0; i < 3; i++) {
for (
size_t j = 0; j < 3; j++) { mc.
addFloat64(cov[i][j]); } }
424 if (mc!=
nullptr && mc->
size() == 9)
426 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(); } }
464 std::vector<Map2DLocation> poses;
468 for (
size_t i=0; i<poses.size(); i++)
484 yCError(LOCALIZATION2DSERVER) <<
"Invalid vocab received";
491 reply.
addString(
"Available commands are:");
493 reply.
addString(
"initLoc <map_name> <x> <y> <angle in degrees>");
499 std::string s = std::string(
"Current Location is: ") + curr_loc.
toString();
510 std::string s = std::string(
"Localization initialized to: ") + init_loc.
toString();
515 yCError(LOCALIZATION2DSERVER) <<
"Invalid command type";
520 if (returnToSender !=
nullptr)
522 reply.
write(*returnToSender);
533 yCInfo(LOCALIZATION2DSERVER) <<
"Running";
542 yCError(LOCALIZATION2DSERVER) <<
"getLocalizationStatus() failed";
553 yCError(LOCALIZATION2DSERVER) <<
"getCurrentPosition() failed";
571 yCWarning(LOCALIZATION2DSERVER,
"The system is not properly localized!");
576 publish_odometry_on_yarp_port();
579 publish_2DLocation_on_yarp_port();
582 publish_odometry_on_ROS_topic();
585 publish_odometry_on_TF_topic();
589 void Localization2DServer::publish_odometry_on_yarp_port()
602 void Localization2DServer::publish_2DLocation_on_yarp_port()
614 temp_loc.
x = std::nan(
"");
615 temp_loc.
y = std::nan(
"");
616 temp_loc.
theta = std::nan(
"");
626 void Localization2DServer::publish_odometry_on_TF_topic()
635 double cosYaw = cos(halfYaw);
636 double sinYaw = sin(halfYaw);
656 void Localization2DServer::publish_odometry_on_ROS_topic()
define control board standard interfaces
constexpr yarp::conf::vocab32_t VOCAB_OK
constexpr yarp::conf::vocab32_t VOCAB_ERR
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_LOCALIZER_POSES
constexpr yarp::conf::vocab32_t VOCAB_INAVIGATION
constexpr yarp::conf::vocab32_t VOCAB_NAV_LOCALIZATION_STOP
constexpr yarp::conf::vocab32_t VOCAB_NAV_SET_INITIAL_POSCOV
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_CURRENT_POS
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_LOCALIZER_STATUS
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_ESTIMATED_ODOM
constexpr yarp::conf::vocab32_t VOCAB_NAV_SET_INITIAL_POS
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_CURRENT_POSCOV
constexpr yarp::conf::vocab32_t VOCAB_NAV_LOCALIZATION_START
#define DEFAULT_THREAD_PERIOD
contains the definition of a Vector type
bool initialize_ROS(yarp::os::Searchable &config)
yarp::dev::Nav2D::Map2DLocation m_current_position
std::string m_child_frame_id
yarp::dev::Nav2D::ILocalization2D * iLoc
yarp::os::BufferedPort< yarp::dev::Nav2D::Map2DLocation > m_2DLocationPort
virtual bool attachAll(const yarp::dev::PolyDriverList &l) override
Attach to a list of objects.
std::string m_2DLocationPortName
bool m_ros_publish_odometry_on_tf
std::string m_robot_frame
yarp::dev::PolyDriver pLoc
virtual bool close() override
Close the DeviceDriver.
std::string m_rpcPortName
yarp::dev::Nav2D::LocalizationStatusEnum m_current_status
virtual bool detachAll() override
Detach the object (you must have first called attach).
yarp::os::BufferedPort< yarp::dev::OdometryData > m_odometryPort
std::string m_odometryPortName
std::string m_parent_frame_id
std::string m_fixed_frame
yarp::os::Publisher< yarp::rosmsg::nav_msgs::Odometry > m_odometry_publisher
yarp::os::Node * m_ros_node
virtual bool open(yarp::os::Searchable &prop) override
Open the DeviceDriver.
yarp::os::Stamp m_loc_stamp
bool m_ros_publish_odometry_on_topic
virtual void run() override
Loop function.
yarp::os::Publisher< yarp::rosmsg::tf2_msgs::TFMessage > m_tf_publisher
yarp::os::Stamp m_odom_stamp
bool m_getdata_using_periodic_thread
yarp::dev::OdometryData m_current_odometry
virtual bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
bool initialize_YARP(yarp::os::Searchable &config)
bool view(T *&x)
Get an interface to the device driver.
std::string map_id
name of the map
double theta
orientation [deg] in the map reference frame
double y
y position of the location [m], expressed in the map reference frame
double x
x position of the location [m], expressed in the map reference frame
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 getCurrentPosition(yarp::dev::Nav2D::Map2DLocation &loc)=0
Gets the current position of the robot w.r.t world reference frame.
virtual bool getEstimatedPoses(std::vector< yarp::dev::Nav2D::Map2DLocation > &poses)=0
Gets a set of pose estimates computed by the localization algorithm.
virtual bool startLocalizationService()=0
Starts the localization service.
virtual bool stopLocalizationService()=0
Stops the localization service.
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...
virtual bool getLocalizationStatus(LocalizationStatusEnum &status)=0
Gets the current status of the localization task.
double base_vel_x
velocity of the robot [m/s] expressed in the robot reference frame
double odom_vel_y
velocity of the robot [m/s] expressed in the world reference frame
double base_vel_theta
angular velocity of the robot [deg/s] expressed in the robot reference frame
double odom_vel_theta
angular velocity of the robot [deg/s] expressed in the world reference frame
double base_vel_y
velocity of the robot [m/s] expressed in the robot reference frame
double odom_x
position of the robot [m], expressed in the world reference frame
double odom_y
position of the robot [m], expressed in the world reference frame
double odom_theta
orientation the robot [deg], expressed in the world reference frame
double odom_vel_x
velocity of the robot [m/s] expressed in the world reference frame
void push(PolyDriver *p, const char *k)
A container for a device driver.
bool isValid() const
Check if device is valid.
bool open(const std::string &txt)
Construct and configure a device by its common name.
void fromRotationMatrix(const yarp::sig::Matrix &R)
Converts a rotation matrix to a quaternion.
A simple collection of objects that can be described and transmitted in a portable way.
void addVocab32(yarp::conf::vocab32_t x)
Places a vocabulary item in the bottle, at the end of the list.
Bottle & addList()
Places an empty nested list in the bottle, at the end of the list.
size_type size() const
Gets the number of elements in the bottle.
bool read(ConnectionReader &reader) override
Set the bottle's value based on input from a network connection.
void addFloat64(yarp::conf::float64_t x)
Places a 64-bit floating point number in the bottle, at the end of the list.
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
bool check(const std::string &key) const override
Check if there exists a property of the given name.
void clear()
Empties the bottle of any objects it contains.
bool write(ConnectionWriter &writer) const override
Output a representation of the bottle to a network connection.
void addInt32(std::int32_t x)
Places a 32-bit integer in the bottle, at the end of the list.
void addString(const char *str)
Places a string in the bottle, at the end of the list.
Value & find(const std::string &key) const override
Gets a value corresponding to a given keyword.
void close() override
Stop port activity.
bool setEnvelope(PortWriter &envelope) override
Set an envelope (e.g., a timestamp) to the next message which will be sent.
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
void interrupt() override
Interrupt any current reads or writes attached to the port.
int getOutputCount() override
Determine how many output connections this port has.
void write(bool forceStrict=false)
Write the current object being returned by BufferedPort::prepare.
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::BufferedPort::write.
An interface for reading from a network connection.
virtual ConnectionWriter * getWriter()=0
Gets a way to reply to the message, if possible.
An interface for writing to a network connection.
An abstraction for a periodic thread.
int getOutputCount() override
Determine how many output connections this port has.
void setReader(PortReader &reader) override
Set an external reader for port data.
void interrupt() override
Interrupt any current reads or writes attached to the port.
void close() override
Stop port activity.
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
A class for storing options and configuration information.
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
void put(const std::string &key, const std::string &value)
Associate the given key with the given string.
void close() override
Stop port activity.
bool topic(const std::string &name)
Set topic to publish to.
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::Publisher::write.
void write(bool forceStrict=false)
Write the current object being returned by Publisher::prepare.
Port & asPort() override
Get the concrete Port being used for communication.
A base class for nested structures that can be searched.
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
virtual Bottle & findGroup(const std::string &key) const =0
Gets a list corresponding to a given keyword.
void update()
Set the timestamp to the current time, and increment the sequence number (wrapping to 0 if the sequen...
double getTime() const
Get the time stamp.
int getCount() const
Get the sequence number.
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
virtual bool isString() const
Checks if value is a string.
virtual yarp::conf::vocab32_t asVocab32() const
Get vocabulary identifier as an integer.
virtual bool asBool() const
Get boolean value.
virtual Bottle * asList() const
Get list value.
virtual bool isVocab32() const
Checks if value is a vocabulary identifier.
virtual std::string asString() const
Get string value.
yarp::rosmsg::geometry_msgs::Pose pose
yarp::rosmsg::geometry_msgs::Point position
yarp::rosmsg::geometry_msgs::Quaternion orientation
yarp::rosmsg::geometry_msgs::Twist twist
yarp::rosmsg::geometry_msgs::Vector3 angular
yarp::rosmsg::geometry_msgs::Vector3 linear
yarp::rosmsg::geometry_msgs::PoseWithCovariance pose
yarp::rosmsg::std_msgs::Header header
std::string child_frame_id
yarp::rosmsg::geometry_msgs::TwistWithCovariance twist
std::vector< yarp::rosmsg::geometry_msgs::TransformStamped > transforms
#define yCInfo(component,...)
#define yCError(component,...)
#define yCTrace(component,...)
#define yCWarning(component,...)
#define yCDebug(component,...)
#define YARP_LOG_COMPONENT(name,...)
@ localization_status_localized_ok
@ localization_status_not_yet_localized
For streams capable of holding different kinds of content, check what they actually have.
yarp::sig::Matrix rpy2dcm(const yarp::sig::Vector &rpy)
Converts roll-pitch-yaw angles in the corresponding dcm (direction cosine matrix) rotation matrix (de...
double now()
Return the current time in seconds, relative to an arbitrary starting point.
An interface to the operating system, including Port based communication.
std::string toString() const
Returns text representation of the location.