6#define _USE_MATH_DEFINES
64 if (config.
check(
"node_name") ==
true)
69 if (config.
check(
"topic_name") ==
true)
101bool MobileBaseVelocityControl_nws_ros::detach()
107bool MobileBaseVelocityControl_nws_ros::attach(
PolyDriver* driver)
bool close() override
Close the DeviceDriver.
commandSubscriber * m_command_subscriber
yarp::os::Node * m_ros_node
std::string m_ros_topic_name
std::string m_ros_node_name
yarp::dev::PolyDriver m_subdev
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
yarp::dev::Nav2D::INavigation2DVelocityActions * m_iNavVel
virtual void onRead(yarp::rosmsg::geometry_msgs::Twist &v) override
void init(yarp::dev::Nav2D::INavigation2DVelocityActions *m_iNavVel)
bool view(T *&x)
Get an interface to the device driver.
virtual yarp::dev::ReturnValue applyVelocityCommand(double x_vel, double y_vel, double theta_vel, double timeout=0.1)=0
Apply a velocity command.
A container for a device driver.
bool close() override
Close the DeviceDriver.
bool isValid() const
Check if device is valid.
A mini-server for performing network communication in the background.
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 Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
bool topic(const std::string &name)
Set topic to subscribe to.
void useCallback(TypedReaderCallback< T > &callback)
#define yCInfo(component,...)
#define yCError(component,...)
#define YARP_LOG_COMPONENT(name,...)
For streams capable of holding different kinds of content, check what they actually have.
An interface to the operating system, including Port based communication.