Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
nav2_velocity_smoother::VelocitySmoother Class Reference

This class that smooths cmd_vel velocities for robot bases. More...

#include <nav2_velocity_smoother/include/nav2_velocity_smoother/velocity_smoother.hpp>

Inheritance diagram for nav2_velocity_smoother::VelocitySmoother:
Inheritance graph
[legend]
Collaboration diagram for nav2_velocity_smoother::VelocitySmoother:
Collaboration graph
[legend]

Public Member Functions

 VelocitySmoother (const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
 A constructor for nav2_velocity_smoother::VelocitySmoother. More...
 
 ~VelocitySmoother ()
 Destructor for nav2_velocity_smoother::VelocitySmoother.
 
double findEtaConstraint (const double v_curr, const double v_cmd, const double accel, const double decel)
 Find the scale factor, eta, which scales axis into acceleration range. More...
 
double applyConstraints (const double v_curr, const double v_cmd, const double accel, const double decel, const double eta)
 Apply acceleration and scale factor constraints. More...
 
- Public Member Functions inherited from nav2::LifecycleNode
 LifecycleNode (const std::string &node_name, const std::string &ns, const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
 A lifecycle node constructor. More...
 
 LifecycleNode (const std::string &node_name, const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
 A lifecycle node constructor with no namespace. More...
 
template<typename ParamType >
ParamType declare_or_get_parameter (const std::string &parameter_name, const ParamType &default_value, const ParameterDescriptor &parameter_descriptor=ParameterDescriptor())
 Declares or gets a parameter. If the parameter is already declared, returns its value; otherwise declares it and returns the default value. More...
 
template<typename MessageT , typename CallbackT >
nav2::Subscription< MessageT >::SharedPtr create_subscription (const std::string &topic_name, CallbackT &&callback, const rclcpp::QoS &qos=nav2::qos::StandardTopicQoS(), const rclcpp::CallbackGroup::SharedPtr &callback_group=nullptr)
 Create a subscription to a topic using Nav2 QoS profiles and SubscriptionOptions. More...
 
template<typename MessageT >
nav2::Publisher< MessageT >::SharedPtr create_publisher (const std::string &topic_name, const rclcpp::QoS &qos=nav2::qos::StandardTopicQoS(), const rclcpp::CallbackGroup::SharedPtr &callback_group=nullptr)
 Create a publisher to a topic using Nav2 QoS profiles and PublisherOptions. More...
 
template<typename ServiceT >
nav2::ServiceClient< ServiceT >::SharedPtr create_client (const std::string &service_name, bool use_internal_executor=false)
 Create a ServiceClient to interface with a service. More...
 
template<typename ServiceT >
nav2::ServiceServer< ServiceT >::SharedPtr create_service (const std::string &service_name, typename nav2::ServiceServer< ServiceT >::CallbackType cb, rclcpp::CallbackGroup::SharedPtr callback_group=nullptr)
 Create a ServiceServer to host with a service. More...
 
template<typename ActionT >
nav2::SimpleActionServer< ActionT >::SharedPtr create_action_server (const std::string &action_name, typename nav2::SimpleActionServer< ActionT >::ExecuteCallback execute_callback, typename nav2::SimpleActionServer< ActionT >::CompletionCallback compl_cb=nullptr, std::chrono::milliseconds server_timeout=std::chrono::milliseconds(500), bool spin_thread=false, const bool realtime=false)
 Create a SimpleActionServer to host with an action. More...
 
template<typename ActionT >
nav2::ActionClient< ActionT >::SharedPtr create_action_client (const std::string &action_name, rclcpp::CallbackGroup::SharedPtr callback_group=nullptr)
 Create a ActionClient to call an action using. More...
 
nav2::LifecycleNode::SharedPtr shared_from_this ()
 Get a shared pointer of this.
 
nav2::LifecycleNode::WeakPtr weak_from_this ()
 Get a shared pointer of this.
 
nav2::CallbackReturn on_error (const rclcpp_lifecycle::State &)
 Abstracted on_error state transition callback, since unimplemented as of 2020 in the managed ROS2 node state machine. More...
 
void autostart ()
 Automatically configure and active the node.
 
virtual void on_rcl_preshutdown ()
 Perform preshutdown activities before our Context is shutdown. Note that this is related to our Context's shutdown sequence, not the lifecycle node state machine.
 
void createBond ()
 Create bond connection to lifecycle manager.
 
void destroyBond ()
 Destroy bond connection to lifecycle manager.
 

Protected Member Functions

nav2::CallbackReturn on_configure (const rclcpp_lifecycle::State &state) override
 Configures parameters and member variables. More...
 
nav2::CallbackReturn on_activate (const rclcpp_lifecycle::State &state) override
 Activates member variables. More...
 
nav2::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &state) override
 Deactivates member variables. More...
 
nav2::CallbackReturn on_cleanup (const rclcpp_lifecycle::State &state) override
 Calls clean up states and resets member variables. More...
 
nav2::CallbackReturn on_shutdown (const rclcpp_lifecycle::State &state) override
 Called when in Shutdown state. More...
 
void inputCommandCallback (const geometry_msgs::msg::Twist::SharedPtr msg)
 Callback for incoming velocity commands. More...
 
void inputCommandStampedCallback (const geometry_msgs::msg::TwistStamped::SharedPtr msg)
 
void smootherTimer ()
 Main worker timer function.
 
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback (std::vector< rclcpp::Parameter > parameters)
 Dynamic reconfigure callback. More...
 
- Protected Member Functions inherited from nav2::LifecycleNode
void printLifecycleNodeNotification ()
 Print notifications for lifecycle node.
 
void register_rcl_preshutdown_callback ()
 
void runCleanups ()
 

Protected Attributes

std::unique_ptr< nav2_util::OdomSmootherodom_smoother_
 
std::unique_ptr< nav2_util::TwistPublishersmoothed_cmd_pub_
 
std::unique_ptr< nav2_util::TwistSubscribercmd_sub_
 
rclcpp::TimerBase::SharedPtr timer_
 
rclcpp::Clock::SharedPtr clock_
 
geometry_msgs::msg::TwistStamped last_cmd_
 
geometry_msgs::msg::TwistStamped::SharedPtr command_
 
double smoothing_frequency_
 
double odom_duration_
 
std::string odom_topic_
 
bool open_loop_
 
bool stopped_ {true}
 
bool scale_velocities_
 
bool is_6dof_
 
std::vector< double > max_velocities_
 
std::vector< double > min_velocities_
 
std::vector< double > max_accels_
 
std::vector< double > max_decels_
 
std::vector< double > deadband_velocities_
 
rclcpp::Duration velocity_timeout_ {0, 0}
 
rclcpp::Time last_command_time_
 
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_
 
- Protected Attributes inherited from nav2::LifecycleNode
std::unique_ptr< rclcpp::PreShutdownCallbackHandle > rcl_preshutdown_cb_handle_ {nullptr}
 
std::shared_ptr< bond::Bond > bond_ {nullptr}
 
double bond_heartbeat_period {0.1}
 
rclcpp::TimerBase::SharedPtr autostart_timer_
 

Additional Inherited Members

- Public Types inherited from nav2::LifecycleNode
using SharedPtr = std::shared_ptr< nav2::LifecycleNode >
 
using WeakPtr = std::weak_ptr< nav2::LifecycleNode >
 
using SharedConstPointer = std::shared_ptr< const nav2::LifecycleNode >
 

Detailed Description

This class that smooths cmd_vel velocities for robot bases.

Definition at line 41 of file velocity_smoother.hpp.

Constructor & Destructor Documentation

◆ VelocitySmoother()

nav2_velocity_smoother::VelocitySmoother::VelocitySmoother ( const rclcpp::NodeOptions &  options = rclcpp::NodeOptions())
explicit

A constructor for nav2_velocity_smoother::VelocitySmoother.

Parameters
optionsAdditional options to control creation of the node.

Definition at line 32 of file velocity_smoother.cpp.

Member Function Documentation

◆ applyConstraints()

double nav2_velocity_smoother::VelocitySmoother::applyConstraints ( const double  v_curr,
const double  v_cmd,
const double  accel,
const double  decel,
const double  eta 
)

Apply acceleration and scale factor constraints.

Parameters
v_currcurrent velocity
v_cmdcommanded velocity
accelmaximum acceleration
decelmaximum deceleration
etaScale factor
Returns
Velocity command

Definition at line 288 of file velocity_smoother.cpp.

Referenced by smootherTimer().

Here is the caller graph for this function:

◆ dynamicParametersCallback()

rcl_interfaces::msg::SetParametersResult nav2_velocity_smoother::VelocitySmoother::dynamicParametersCallback ( std::vector< rclcpp::Parameter >  parameters)
protected

Dynamic reconfigure callback.

Parameters
parametersParameter list to change

Definition at line 492 of file velocity_smoother.cpp.

References nav2::LifecycleNode::shared_from_this(), and smootherTimer().

Referenced by on_activate().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ findEtaConstraint()

double nav2_velocity_smoother::VelocitySmoother::findEtaConstraint ( const double  v_curr,
const double  v_cmd,
const double  accel,
const double  decel 
)

Find the scale factor, eta, which scales axis into acceleration range.

Parameters
v_currcurrent velocity
v_cmdcommanded velocity
accelmaximum acceleration
decelmaximum deceleration
Returns
Scale factor, eta

Definition at line 257 of file velocity_smoother.cpp.

Referenced by smootherTimer().

Here is the caller graph for this function:

◆ inputCommandCallback()

void nav2_velocity_smoother::VelocitySmoother::inputCommandCallback ( const geometry_msgs::msg::Twist::SharedPtr  msg)
protected

Callback for incoming velocity commands.

Parameters
msgTwist message

Definition at line 249 of file velocity_smoother.cpp.

Referenced by on_configure().

Here is the caller graph for this function:

◆ on_activate()

nav2::CallbackReturn nav2_velocity_smoother::VelocitySmoother::on_activate ( const rclcpp_lifecycle::State &  state)
overrideprotected

Activates member variables.

Parameters
stateLifeCycle Node's state
Returns
Success or Failure

Definition at line 180 of file velocity_smoother.cpp.

References nav2::LifecycleNode::createBond(), dynamicParametersCallback(), and smootherTimer().

Here is the call graph for this function:

◆ on_cleanup()

nav2::CallbackReturn nav2_velocity_smoother::VelocitySmoother::on_cleanup ( const rclcpp_lifecycle::State &  state)
overrideprotected

Calls clean up states and resets member variables.

Parameters
stateLifeCycle Node's state
Returns
Success or Failure

Definition at line 216 of file velocity_smoother.cpp.

Referenced by on_configure().

Here is the caller graph for this function:

◆ on_configure()

nav2::CallbackReturn nav2_velocity_smoother::VelocitySmoother::on_configure ( const rclcpp_lifecycle::State &  state)
overrideprotected

Configures parameters and member variables.

Parameters
stateLifeCycle Node's state
Returns
Success or Failure

Definition at line 47 of file velocity_smoother.cpp.

References inputCommandCallback(), on_cleanup(), and nav2::LifecycleNode::shared_from_this().

Here is the call graph for this function:

◆ on_deactivate()

nav2::CallbackReturn nav2_velocity_smoother::VelocitySmoother::on_deactivate ( const rclcpp_lifecycle::State &  state)
overrideprotected

Deactivates member variables.

Parameters
stateLifeCycle Node's state
Returns
Success or Failure

Definition at line 198 of file velocity_smoother.cpp.

References nav2::LifecycleNode::destroyBond().

Here is the call graph for this function:

◆ on_shutdown()

nav2::CallbackReturn nav2_velocity_smoother::VelocitySmoother::on_shutdown ( const rclcpp_lifecycle::State &  state)
overrideprotected

Called when in Shutdown state.

Parameters
stateLifeCycle Node's state
Returns
Success or Failure

Definition at line 226 of file velocity_smoother.cpp.


The documentation for this class was generated from the following files: