6#define _USE_MATH_DEFINES
35#define DEFAULT_THREAD_PERIOD 0.01
98 if (!config.
check(
"period"))
109 if (!config.
check(
"publish_odometry"))
114 if (!config.
check(
"publish_tf"))
120 if (!config.
check(
"yarp_base_name"))
154 if (params.
check(
"parent_frame_id"))
159 if (params.
check(
"child_frame_id"))
164 if (params.
check(
"topic_name"))
169 if (params.
check(
"node_name"))
243 bool ok = command.
read(connection);
253 reply.
addString(
"No commands currently available:");
285 if (
m_current_status == LocalizationStatusEnum::localization_status_localized_ok)
312 publish_odometry_on_ROS_topic();
315 publish_odometry_on_TF_topic();
319void Localization2D_nws_ros::publish_odometry_on_TF_topic()
322 yarp::rosmsg::geometry_msgs::TransformStamped transform;
330 transform.transform.rotation.x = 0;
331 transform.transform.rotation.y = 0;
332 transform.transform.rotation.z =
sinYaw;
333 transform.transform.rotation.w =
cosYaw;
336 transform.transform.translation.z = 0;
337 if (
rosData.transforms.size() == 0)
339 rosData.transforms.push_back(transform);
343 rosData.transforms[0] = transform;
349void Localization2D_nws_ros::publish_odometry_on_ROS_topic()
362 odom.pose.pose.position.z = 0;
369 odom.pose.pose.orientation.x = q.
x();
370 odom.pose.pose.orientation.y = q.
y();
371 odom.pose.pose.orientation.z = q.
z();
372 odom.pose.pose.orientation.w = q.
w();
377 odom.twist.twist.linear.z = 0;
378 odom.twist.twist.angular.x = 0;
379 odom.twist.twist.angular.y = 0;
define control board standard interfaces
constexpr yarp::conf::vocab32_t VOCAB_ERR
#define DEFAULT_THREAD_PERIOD
contains the definition of a Vector type
std::string m_robot_frame
bool m_enable_publish_odometry_tf
std::string m_fixed_frame
bool close() override
Close the DeviceDriver.
std::string m_odom_topic_name
bool initialize_YARP(yarp::os::Searchable &config)
std::string m_parent_frame_id
yarp::dev::OdometryData m_current_odometry
yarp::os::Publisher< yarp::rosmsg::nav_msgs::Odometry > m_odometry_publisher
yarp::os::Stamp m_loc_stamp
yarp::dev::Nav2D::ILocalization2D * iLoc
std::string m_rpcPortName
yarp::dev::Nav2D::Map2DLocation m_current_position
bool open(yarp::os::Searchable &prop) override
Open the DeviceDriver.
yarp::dev::Nav2D::LocalizationStatusEnum m_current_status
yarp::os::Stamp m_odom_stamp
bool m_enable_publish_odometry_topic
yarp::os::Publisher< yarp::rosmsg::tf2_msgs::TFMessage > m_tf_publisher
bool detach() override
Detach the object (you must have first called attach).
bool attach(yarp::dev::PolyDriver *driver) override
Attach to another object.
std::string m_child_frame_id
void run() override
Loop function.
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
bool initialize_ROS(yarp::os::Searchable &config)
bool view(T *&x)
Get an interface to the device driver.
virtual yarp::dev::ReturnValue getLocalizationStatus(LocalizationStatusEnum &status)=0
Gets the current status of the localization task.
virtual yarp::dev::ReturnValue getCurrentPosition(yarp::dev::Nav2D::Map2DLocation &loc)=0
Gets the current position of the robot w.r.t world reference frame.
virtual yarp::dev::ReturnValue getEstimatedOdometry(yarp::dev::OdometryData &odom)=0
Gets the estimated odometry the robot, including its velocity expressed in the world and in the local...
double base_vel_x
velocity of the robot [m/s] expressed in the robot reference frame
double base_vel_theta
angular velocity of the robot [deg/s] expressed in the robot 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
A container for a device driver.
bool isValid() const
Check if device is valid.
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.
bool read(ConnectionReader &reader) override
Set the bottle's value based on input from a network connection.
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
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 addString(const char *str)
Places a string in the bottle, at the end of the list.
A mini-server for performing network communication in the background.
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.
bool setPeriod(double period)
Set the (new) period of the thread.
bool isRunning() const
Returns true when the thread is started, false otherwise.
bool start()
Call this to start the thread.
void stop()
Call this to stop the thread, this call blocks until the thread is terminated (and releaseThread() ca...
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 close() override
Stop port activity.
bool topic(const std::string &name)
Set topic to publish to.
Port & asPort() override
Get the concrete Port being used for communication.
void write(bool forceStrict=false)
Write the current object being returned by Publisher::prepare.
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::Publisher::write.
A base class for nested structures that can be searched.
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 Value & find(const std::string &key) const =0
Gets a value 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 bool isString() const
Checks if value is a string.
virtual std::string asString() const
Get string value.
#define yCInfo(component,...)
#define yCError(component,...)
#define yCTrace(component,...)
#define yCWarning(component,...)
#define yCDebug(component,...)
#define YARP_LOG_COMPONENT(name,...)
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.