Aerial Robotics IITK
  • Introduction
  • Danger Zone
  • Tutorials
    • Workspace Setup
      • Installing Ubuntu
      • Basic Linux Setup
      • Spruce up your space
      • ROS Setup
      • PX4 Setup
        • PX4 Toolchain Setup
      • Ardupilot Setup
      • Installing Ground Control Station
        • QGroundControl
        • Mission Planner
      • ArduPilot Setup on Docker
      • PX4 Setup on Docker
    • How to Write a ROS Package
      • ROS Package
      • Node Handles, Parameters, and Topics
      • Coding Standards
      • Custom mavros message
      • Transformations
      • Conversions
    • Cheatsheets
      • CMakeCheatsheet
      • GitCheatsheet
      • LatexCheatsheet
      • Markdown Cheatsheet
    • Miscellaneous
      • Odroid XU4 Setup
      • Simulation using Offboard Control
        • Enable Offboard Mode in PX4
      • Writing a UDev rule
      • Sensor fusion
    • Reference wiki links
  • Concepts
    • Quaternions
      • Theory
    • Kalman Filters
    • Rotations
    • Path Planning
      • Grassfire Algorithm
      • Dijkstra Algorithm
      • A* Algorithm
      • Probabilistic Roadmap
      • RRT Algorithm
      • Visibility Graph Analysis
    • Lectures
      • Aerial Robotics
      • Avionics
      • Control Systems: Introduction
      • Control Systems: Models
      • Inter IIT Tech Meet 2018
      • Kalman Filters
      • Linux and Git
      • Git Tutorial
      • ROS
      • Rotorcraft
      • Software Training
  • Control System
    • Model Predictive Control
      • System Identification
      • Sample SysId Launch Files
      • Running MPC
        • MPC with Rotors
        • MPC with PX4 Sim
        • MPC with ROS
      • References
    • PID Controller
      • Introduction
      • Basic Theory
  • Estimation
    • Visual-Inertial Odometry
      • Hardware Requirements
      • Visual-Inertial Sensing
      • DIYing a VI-Sensor
    • Setup with VICON
    • Odometry from pose data
  • Computer Vision
    • Intel RealSense D435i setup for ROS Noetic
    • IntelRealSense D435i Calibration
    • Camera Calibration
    • ArUco ROS
  • Machine Learning
    • Datasets
  • Hardware Integration
    • Configuring Radio Telemetry
    • Setting up RTK + GPS
    • Integration of Sensors with PixHawk
      • Connecting Lidar-lite through I2C
    • Connections
    • Setting up Offboard Mission
      • Setting up Companion Computer
        • Raspberry Pi 4B Setup
        • Jetson TX2 Setup
      • Communication Setup
      • Guided mode
    • Miscellaneous
  • Resources
    • Open-source algorithms and resources
    • Courses
      • State Space Modelling of a Multirotor
      • Path Planning Lecture
      • Introduction to AI in Robotics
      • RRT, RRT* and RRT*- Path Planning Algorithms
    • Useful Reading Links
      • Aerial Robotics
      • Books
      • Computer Vision and Image Processing
      • Courses on AI and Robotics
      • Deep Neural Network
      • Dynamics and Controls system
      • Motion Planning
      • Probabilistic Robotics
      • Programming
      • Robotics Hardware
      • Miscellaneous and Awesome
    • Online Purchase websites
  • Competitions
    • Inter-IIT TechMeet 8.0
    • Inter-IIT TechMeet 9.0
    • IMAV 2019, Madrid, Spain
    • Inter-IIT TechMeet 10.0
    • Inter-IIT TechMeet 11.0
Powered by GitBook
On this page
  • package.xml
  • CMakeLists.txt
  • Folder/file structure

Was this helpful?

  1. Tutorials
  2. How to Write a ROS Package

ROS Package

How to package.

package.xml

Use package format 2.0, which removes the distinction between <run_depend> and <build_depend> and makes this more compact.

Use spaces, 2-wide as indentation.

Example:

<?xml version="1.0"?>
<package format="2">
  <name>mav_local_planner</name>
  <version>0.0.0</version>
  <description>
    Local planner with multiple configurable components for planning
    straight-line paths to waypoints, checking global plans for collisions,
    and doing local obstacle avoidance.
  </description>

  <maintainer email="helenoleynikova@gmail.com">Helen Oleynikova</maintainer>

  <license>BSD</license>

  <buildtool_depend>catkin</buildtool_depend>
  <buildtool_depend>catkin_simple</buildtool_depend>

  <depend>mav_msgs</depend>
  <depend>mav_planning_utils</depend>
  <depend>planner_ompl</depend>
  <depend>planner_base</depend>
  <depend>planning_msgs</depend>
  <depend>roscpp</depend>
  <depend>tf</depend>
</package>

CMakeLists.txt

A few tips:

  • catkin_simple(ALL_DEPS_REQUIRED) will make sure that all dependencies in the package.xml above are found on the system and loaded.

  • Make a library called ${PROJECT_NAME} and link any executables against it.

  • If you're outputting messages, this is done automatically by catkin simple. However, if you have executables and messages in the same package (prefer not to do this, just have a whatever_msgs package instead), you need to add this to after your executable/library so that things are built in the right order: add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS})

See the documentation at the link above, and this example:

cmake_minimum_required(VERSION 2.8.3)
project(mav_local_planner)

find_package(catkin_simple REQUIRED)
catkin_simple(ALL_DEPS_REQUIRED)

add_definitions(-std=c++11)

#############
# LIBRARIES #
#############
cs_add_library(${PROJECT_NAME}
  src/trajectory_sampler.cpp
)

############
# BINARIES #
############
cs_add_executable(local_planner_node
  src/local_planner_node.cpp
)
target_link_libraries(local_planner_node ${PROJECT_NAME})

##########
# EXPORT #
##########
cs_install()
cs_export()

Folder/file structure

Keep in mind:

  • Your headers should be in include/PACKAGE_NAME/header.h

  • Your source files should be in the src/ folder.

  • Ideally, if you have ROS parameters in your node, you should have the default values and descriptions in a .yaml file in the cfg folder.

mav_local_planner
├── CMakeLists.txt
├── cfg
│   └── default_local_planner_params.yaml
├── include
│   └── mav_local_planner
│       └── trajectory_sampler.h
├── package.xml
└── src
    ├── local_planner_node.cpp
    └── trajectory_sampler.cpp

Example default_local_planner_params.yaml. Always have units when available!

# This file is meant as an example and explanation of the planning params.
# Everything in the base is for the local planner.
local_planning_horizon: 3 # [sec], how far forward to sample trajectories
trajectory_sampling_dt: 0.01 # [sec], how often to sample the trajectory for the controller.
collision_sampling_dt: 0.1 # [sec], how often to check for collisions along the path.
command_publishing_dt: 1.0 # [sec], how often to publish new commands to position controller.
mpc_prediction_horizon: 30 # [timesteps], how many timesteps ahead to publish in addition to the rate

# What kind of planners, obstacle avoidance, etc. to use.
use_obstacle_avoidance: false
# Whether to publish any new trajectories immediately or wait for start
# service call.
autostart: true
PreviousHow to Write a ROS PackageNextNode Handles, Parameters, and Topics

Last updated 5 years ago

Was this helpful?

You should use rather than the old-style catkin lists, since they make everything easier. Use spaces, 2-wide as indentation.

Your package should look something like the example below. See the for more details.

catkin_simple
ROS Package Documentation