Skip to content

Commit

Permalink
Fix typos
Browse files Browse the repository at this point in the history
Signed-off-by: Tony Najjar <[email protected]>
  • Loading branch information
tonynajjar committed Dec 13, 2024
1 parent c0ba65d commit e4a4d38
Show file tree
Hide file tree
Showing 155 changed files with 312 additions and 312 deletions.
4 changes: 2 additions & 2 deletions Doxyfile
Original file line number Diff line number Diff line change
Expand Up @@ -1451,8 +1451,8 @@ EXT_LINKS_IN_WINDOW = NO

FORMULA_FONTSIZE = 10

# Use the FORMULA_TRANPARENT tag to determine whether or not the images
# generated for formulas are transparent PNGs. Transparent PNGs are not
# Use the FORMULA_TRANSPARENT tag to determine whether or not the images
# generated for formulas are transparent ONGs. Transparent ONGs are not
# supported properly for IE 6.0, but are supported on all modern browsers.
#
# Note that when changing this option you need to delete any form_*.png files in
Expand Down
4 changes: 2 additions & 2 deletions doc/requirements/requirements.md
Original file line number Diff line number Diff line change
Expand Up @@ -199,7 +199,7 @@ ME005 | Mission Execution.Command Sequencing | 1 | The Mission Execution module
ME006 | Mission Execution.Logging | 1 | The Mission Execution module SHOULD log its activity. | In case of forensic analysis of a safety event, for example.
ME007 | Mission Execution.Feedback.Inputs.Error Recovery | 1 | Upon receipt of a downstream failure (unable to execute the Navigation Command), the Mission Execution module SHOULD attempt to recover and continue execution of the mission.
ME008 | Mission Execution.Feedback.Outputs.Progress Notification | 1 | The Mission Execution module SHALL provide progress notifications on the execution of the mission. | Intermediate steps of interest.
ME009 | Mission Execution.Feedback.Outputs.Mission Completed | 1 | Upon successfull completion of the mission, the Mission Execution module SHALL output a corresponding notification.
ME009 | Mission Execution.Feedback.Outputs.Mission Completed | 1 | Upon successful completion of the mission, the Mission Execution module SHALL output a corresponding notification.
ME010 | Mission Execution.Feedback.Outputs.Mission Canceled | 1 | Upon receiving a cancellation command and cancelling the mission, the Mission Execution module SHALL output a corresponding notification.
ME011 | Mission Execution.Feedback.Outputs.Mission Failure | 1 | If the Mission Execution module is unable to execute the mission, it MUST output a failure notification. | This would be received by the user-level interface and could necessitate user intervention, such as having a remote operating center where the remote operator "rescues" the robot.
ME012 | Mission Execution.Safe State Upon Failure | 1 | If the Mission Execution module is unable to execute the mission, it MUST direct the robot to a safe state. | The failure could be for a variety of reasons - sensor failures, algorithmic failure, a collision, etc.
Expand Down Expand Up @@ -267,7 +267,7 @@ There are a few support modules and subsystems that are not part of the Navigati

### 2.4.1 Mapping

The map data format should be capable of describing typical indoor and outdoor environments encoutered by the robots.
The map data format should be capable of describing typical indoor and outdoor environments encountered by the robots.

Id | Handle | Priority | Description | Notes
-- | ------ | -------- | ----------- | -----
Expand Down
2 changes: 1 addition & 1 deletion nav2_amcl/include/nav2_amcl/amcl_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -112,7 +112,7 @@ class AmclNode : public nav2_util::LifecycleNode
typedef struct
{
double weight; // Total weight (weights sum to 1)
pf_vector_t pf_pose_mean; // Mean of pose esimate
pf_vector_t pf_pose_mean; // Mean of pose estimate
pf_matrix_t pf_pose_cov; // Covariance of pose estimate
} amcl_hyp_t;

Expand Down
2 changes: 1 addition & 1 deletion nav2_amcl/include/nav2_amcl/pf/pf.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -145,7 +145,7 @@ pf_t * pf_alloc(
// Free an existing filter
void pf_free(pf_t * pf);

// Initialize the filter using a guassian
// Initialize the filter using a gaussian
void pf_init(pf_t * pf, pf_vector_t mean, pf_matrix_t cov);

// Initialize the filter using some model
Expand Down
12 changes: 6 additions & 6 deletions nav2_amcl/include/nav2_amcl/sensors/laser/laser.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ class Laser
* @brief Run a sensor update on laser
* @param pf Particle filter to use
* @param data Laser data to use
* @return if it was succesful
* @return if it was successful
*/
virtual bool sensorUpdate(pf_t * pf, LaserData * data) = 0;

Expand Down Expand Up @@ -123,7 +123,7 @@ class BeamModel : public Laser
* @brief Run a sensor update on laser
* @param pf Particle filter to use
* @param data Laser data to use
* @return if it was succesful
* @return if it was successful
*/
bool sensorUpdate(pf_t * pf, LaserData * data);

Expand Down Expand Up @@ -153,7 +153,7 @@ class LikelihoodFieldModel : public Laser
* @brief Run a sensor update on laser
* @param pf Particle filter to use
* @param data Laser data to use
* @return if it was succesful
* @return if it was successful
*/
bool sensorUpdate(pf_t * pf, LaserData * data);

Expand All @@ -162,7 +162,7 @@ class LikelihoodFieldModel : public Laser
* @brief Perform the update function
* @param data Laser data to use
* @param pf Particle filter to use
* @return if it was succesful
* @return if it was successful
*/
static double sensorFunction(LaserData * data, pf_sample_set_t * set);
};
Expand All @@ -187,7 +187,7 @@ class LikelihoodFieldModelProb : public Laser
* @brief Run a sensor update on laser
* @param pf Particle filter to use
* @param data Laser data to use
* @return if it was succesful
* @return if it was successful
*/
bool sensorUpdate(pf_t * pf, LaserData * data);

Expand All @@ -196,7 +196,7 @@ class LikelihoodFieldModelProb : public Laser
* @brief Perform the update function
* @param data Laser data to use
* @param pf Particle filter to use
* @return if it was succesful
* @return if it was successful
*/
static double sensorFunction(LaserData * data, pf_sample_set_t * set);
bool do_beamskip_;
Expand Down
2 changes: 1 addition & 1 deletion nav2_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1584,7 +1584,7 @@ AmclNode::initServices()
void
AmclNode::initOdometry()
{
// TODO(mjeronimo): We should handle persistance of the last known pose of the robot. We could
// TODO(mjeronimo): We should handle persistence of the last known pose of the robot. We could
// then read that pose here and initialize using that.

// When pausing and resuming, remember the last robot pose so we don't start at 0:0 again
Expand Down
4 changes: 2 additions & 2 deletions nav2_amcl/src/pf/pf.c
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ pf_t * pf_alloc(
// the max error between the true distribution and the estimated
// distribution. [z] is the upper standard normal quantile for (1 -
// p), where p is the probability that the error on the estimated
// distrubition will be less than [err].
// distribution will be less than [err].
pf->pop_err = 0.01;
pf->pop_z = 3;
pf->dist_threshold = 0.5;
Expand Down Expand Up @@ -123,7 +123,7 @@ void pf_free(pf_t * pf)
free(pf);
}

// Initialize the filter using a guassian
// Initialize the filter using a gaussian
void pf_init(pf_t * pf, pf_vector_t mean, pf_matrix_t cov)
{
int i;
Expand Down
2 changes: 1 addition & 1 deletion nav2_amcl/src/pf/pf_draw.c
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ void pf_draw_samples(pf_t * pf, rtk_fig_t * fig, int max_samples)
}


// Draw the hitogram (kd tree)
// Draw the histogram (kd tree)
void pf_draw_hist(pf_t * pf, rtk_fig_t * fig)
{
pf_sample_set_t * set;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -218,7 +218,7 @@ class BtActionServer
// The blackboard shared by all of the nodes in the tree
BT::Blackboard::Ptr blackboard_;

// The XML file that cointains the Behavior Tree to create
// The XML file that contains the Behavior Tree to create
std::string current_bt_xml_filename_;
std::string default_bt_xml_filename_;

Expand Down
2 changes: 1 addition & 1 deletion nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -238,7 +238,7 @@ T1 deconflictPortAndParamFrame(
/**
* @brief Try reading an import port first, and if that doesn't work
* fallback to reading directly the blackboard.
* The blackboard must be passed explitly because config() is private in BT.CPP 4.X
* The blackboard must be passed explicitly because config() is private in BT.CPP 4.X
*
* @param bt_node node
* @param blackboard the blackboard ovtained with node->config().blackboard
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ class DriveOnHeadingAction : public BtActionNode<nav2_msgs::action::DriveOnHeadi
BT::NodeStatus on_cancelled() override;

private:
bool initalized_;
bool initialized_;
};

} // namespace nav2_behavior_tree
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ class IsPathValidCondition : public BT::ConditionNode
private:
rclcpp::Node::SharedPtr node_;
rclcpp::Client<nav2_msgs::srv::IsPathValid>::SharedPtr client_;
// The timeout value while waiting for a responce from the
// The timeout value while waiting for a response from the
// is path valid service
std::chrono::milliseconds server_timeout_;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -101,7 +101,7 @@ class IsStuckCondition : public BT::ConditionNode
// Calculated states
double current_accel_;

// Robot specific paramters
// Robot specific parameters
double brake_accel_limit_;
};

Expand Down
12 changes: 6 additions & 6 deletions nav2_behavior_tree/nav2_tree_nodes.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<!--
For instructions on using Groot and description of the following BehaviorTree nodes,
please refer to the groot_instructions.md and REAMDE.md respectively located in the
please refer to the groot_instructions.md and README.md respectively located in the
nav2_behavior_tree package.
-->
<root BTCPP_format="4">
Expand Down Expand Up @@ -171,31 +171,31 @@
<Action ID="PlannerSelector">
<input_port name="topic_name">Name of the topic to receive planner selection commands</input_port>
<input_port name="default_planner">Default planner of the planner selector</input_port>
<output_port name="selected_planner">Name of the selected planner received from the topic subcription</output_port>
<output_port name="selected_planner">Name of the selected planner received from the topic subscription</output_port>
</Action>

<Action ID="ControllerSelector">
<input_port name="topic_name">Name of the topic to receive controller selection commands</input_port>
<input_port name="default_controller">Default controller of the controller selector</input_port>
<output_port name="selected_controller">Name of the selected controller received from the topic subcription</output_port>
<output_port name="selected_controller">Name of the selected controller received from the topic subscription</output_port>
</Action>

<Action ID="SmootherSelector">
<input_port name="topic_name">Name of the topic to receive smoother selection commands</input_port>
<input_port name="default_smoother">Default smoother of the smoother selector</input_port>
<output_port name="selected_smoother">Name of the selected smoother received from the topic subcription</output_port>
<output_port name="selected_smoother">Name of the selected smoother received from the topic subscription</output_port>
</Action>

<Action ID="GoalCheckerSelector">
<input_port name="topic_name">Name of the topic to receive goal checker selection commands</input_port>
<input_port name="default_goal_checker">Default goal checker of the controller selector</input_port>
<output_port name="selected_goal_checker">Name of the selected goal checker received from the topic subcription</output_port>
<output_port name="selected_goal_checker">Name of the selected goal checker received from the topic subscription</output_port>
</Action>

<Action ID="ProgressCheckerSelector">
<input_port name="topic_name">Name of the topic to receive progress checker selection commands</input_port>
<input_port name="default_progress_checker">Default progress checker of the controller selector</input_port>
<output_port name="selected_progress_checker">Name of the selected progress checker received from the topic subcription</output_port>
<output_port name="selected_progress_checker">Name of the selected progress checker received from the topic subscription</output_port>
</Action>

<Action ID="Spin">
Expand Down
6 changes: 3 additions & 3 deletions nav2_behavior_tree/plugins/action/drive_on_heading_action.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ DriveOnHeadingAction::DriveOnHeadingAction(
const std::string & action_name,
const BT::NodeConfiguration & conf)
: BtActionNode<nav2_msgs::action::DriveOnHeading>(xml_tag_name, action_name, conf),
initalized_(false)
initialized_(false)
{
}

Expand All @@ -47,12 +47,12 @@ void DriveOnHeadingAction::initialize()
goal_.speed = speed;
goal_.time_allowance = rclcpp::Duration::from_seconds(time_allowance);
goal_.disable_collision_checks = disable_collision_checks;
initalized_ = true;
initialized_ = true;
}

void DriveOnHeadingAction::on_tick()
{
if (!initalized_) {
if (!initialized_) {
initialize();
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,10 +25,10 @@
#include "utils/test_behavior_tree_fixture.hpp"


class RemoveInCollisionGoalsSucessService : public TestService<nav2_msgs::srv::GetCosts>
class RemoveInCollisionGoalsSuccessService : public TestService<nav2_msgs::srv::GetCosts>
{
public:
RemoveInCollisionGoalsSucessService()
RemoveInCollisionGoalsSuccessService()
: TestService("/global_costmap/get_cost_global_costmap")
{}

Expand Down Expand Up @@ -113,7 +113,7 @@ class RemoveInCollisionGoalsTestFixture : public ::testing::Test
{
tree_.reset();
}
static std::shared_ptr<RemoveInCollisionGoalsSucessService> success_server_;
static std::shared_ptr<RemoveInCollisionGoalsSuccessService> success_server_;
static std::shared_ptr<RemoveInCollisionGoalsFailureService> failure_server_;

protected:
Expand All @@ -126,7 +126,7 @@ class RemoveInCollisionGoalsTestFixture : public ::testing::Test
rclcpp::Node::SharedPtr RemoveInCollisionGoalsTestFixture::node_ = nullptr;

BT::NodeConfiguration * RemoveInCollisionGoalsTestFixture::config_ = nullptr;
std::shared_ptr<RemoveInCollisionGoalsSucessService>
std::shared_ptr<RemoveInCollisionGoalsSuccessService>
RemoveInCollisionGoalsTestFixture::success_server_ = nullptr;
std::shared_ptr<RemoveInCollisionGoalsFailureService>
RemoveInCollisionGoalsTestFixture::failure_server_ = nullptr;
Expand Down Expand Up @@ -237,7 +237,7 @@ int main(int argc, char ** argv)

// initialize service and spin on new thread
RemoveInCollisionGoalsTestFixture::success_server_ =
std::make_shared<RemoveInCollisionGoalsSucessService>();
std::make_shared<RemoveInCollisionGoalsSuccessService>();
std::thread success_server_thread([]() {
rclcpp::spin(RemoveInCollisionGoalsTestFixture::success_server_);
});
Expand Down
2 changes: 1 addition & 1 deletion nav2_behaviors/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@ The package defines:
- A `TimedBehavior` template which is used as a base class to implement specific timed behavior action server - but not required.
- The `Backup`, `DriveOnHeading`, `Spin` and `Wait` behaviors.

The only required class a behavior must derive from is the `nav2_core/behavior.hpp` class, which implements the pluginlib interface the behavior server will use to dynamically load your behavior. The `nav2_behaviors/timed_behavior.hpp` derives from this class and implements a generic action server for a timed behavior behavior (e.g. calls an implmentation function on a regular time interval to compute a value) but **this is not required** if it is not helpful. A behavior does not even need to be an action if you do not wish, it may be a service or other interface. However, most motion and behavior primitives are probably long-running and make sense to be modeled as actions, so the provided `timed_behavior.hpp` helps in managing the complexity to simplify new behavior development, described more below.
The only required class a behavior must derive from is the `nav2_core/behavior.hpp` class, which implements the pluginlib interface the behavior server will use to dynamically load your behavior. The `nav2_behaviors/timed_behavior.hpp` derives from this class and implements a generic action server for a timed behavior behavior (e.g. calls an implementation function on a regular time interval to compute a value) but **this is not required** if it is not helpful. A behavior does not even need to be an action if you do not wish, it may be a service or other interface. However, most motion and behavior primitives are probably long-running and make sense to be modeled as actions, so the provided `timed_behavior.hpp` helps in managing the complexity to simplify new behavior development, described more below.

The value of the centralized behavior server is to **share resources** amongst several behaviors that would otherwise be independent nodes. Subscriptions to TF, costmaps, and more can be quite heavy and add non-trivial compute costs to a robot system. By combining these independent behaviors into a single server, they may share these resources while retaining complete independence in execution and interface.

Expand Down
6 changes: 3 additions & 3 deletions nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -198,7 +198,7 @@ class TimedBehavior : public nav2_core::Behavior
std::string global_frame_;
std::string robot_base_frame_;
double transform_tolerance_;
rclcpp::Duration elasped_time_{0, 0};
rclcpp::Duration elapsed_time_{0, 0};

// Clock
rclcpp::Clock::SharedPtr clock_;
Expand Down Expand Up @@ -236,7 +236,7 @@ class TimedBehavior : public nav2_core::Behavior
rclcpp::WallRate loop_rate(cycle_frequency_);

while (rclcpp::ok()) {
elasped_time_ = clock_->now() - start_time;
elapsed_time_ = clock_->now() - start_time;
// TODO(orduno) #868 Enable preempting a Behavior on-the-fly without stopping
if (action_server_->is_preempt_requested()) {
RCLCPP_ERROR(
Expand All @@ -253,7 +253,7 @@ class TimedBehavior : public nav2_core::Behavior
if (action_server_->is_cancel_requested()) {
RCLCPP_INFO(logger_, "Canceling %s", behavior_name_.c_str());
stopRobot();
result->total_elapsed_time = elasped_time_;
result->total_elapsed_time = elapsed_time_;
onActionCompletion(result);
action_server_->terminate_all(result);
return;
Expand Down
2 changes: 1 addition & 1 deletion nav2_behaviors/plugins/assisted_teleop.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@ void AssistedTeleop::onActionCompletion(std::shared_ptr<AssistedTeleopActionResu

ResultStatus AssistedTeleop::onCycleUpdate()
{
feedback_->current_teleop_duration = elasped_time_;
feedback_->current_teleop_duration = elapsed_time_;
action_server_->publish_feedback(feedback_);

rclcpp::Duration time_remaining = end_time_ - this->clock_->now();
Expand Down
2 changes: 1 addition & 1 deletion nav2_bringup/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ ros2 launch nav2_bringup cloned_multi_tb3_simulation_launch.py robots:="robot1={

#### Unique

There are two robots including name and intitial pose are hard-coded in the launch script. Two separated unique robots are required params file (`nav2_multirobot_params_1.yaml`, `nav2_multirobot_params_2.yaml`) for each robot to bring up.
There are two robots including name and initial pose are hard-coded in the launch script. Two separated unique robots are required params file (`nav2_multirobot_params_1.yaml`, `nav2_multirobot_params_2.yaml`) for each robot to bring up.

If you want to bringup more than two robots, you should modify the `unique_multi_tb3_simulation_launch.py` script.

Expand Down
2 changes: 1 addition & 1 deletion nav2_bringup/launch/localization_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ def generate_launch_description():
declare_container_name_cmd = DeclareLaunchArgument(
'container_name',
default_value='nav2_container',
description='the name of conatiner that nodes will load in if use composition',
description='the name of container that nodes will load in if use composition',
)

declare_use_respawn_cmd = DeclareLaunchArgument(
Expand Down
2 changes: 1 addition & 1 deletion nav2_bringup/launch/navigation_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -108,7 +108,7 @@ def generate_launch_description():
declare_container_name_cmd = DeclareLaunchArgument(
'container_name',
default_value='nav2_container',
description='the name of conatiner that nodes will load in if use composition',
description='the name of container that nodes will load in if use composition',
)

declare_use_respawn_cmd = DeclareLaunchArgument(
Expand Down
2 changes: 1 addition & 1 deletion nav2_bringup/launch/tb3_simulation_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -198,7 +198,7 @@ def generate_launch_description():
}.items(),
)
# The SDF file for the world is a xacro file because we wanted to
# conditionally load the SceneBroadcaster plugin based on wheter we're
# conditionally load the SceneBroadcaster plugin based on whether we're
# running in headless mode. But currently, the Gazebo command line doesn't
# take SDF strings for worlds, so the output of xacro needs to be saved into
# a temporary file and passed to Gazebo.
Expand Down
2 changes: 1 addition & 1 deletion nav2_bringup/launch/tb4_simulation_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -200,7 +200,7 @@ def generate_launch_description():
)

# The SDF file for the world is a xacro file because we wanted to
# conditionally load the SceneBroadcaster plugin based on wheter we're
# conditionally load the SceneBroadcaster plugin based on whether we're
# running in headless mode. But currently, the Gazebo command line doesn't
# take SDF strings for worlds, so the output of xacro needs to be saved into
# a temporary file and passed to Gazebo.
Expand Down
Loading

0 comments on commit e4a4d38

Please sign in to comment.