Skip to content

Create a plugin

Jeremie Deray edited this page May 23, 2017 · 16 revisions

Create a plugin


The laser_odometry scheme package relies on pluginlib.
The plugin is a simple wrapper between a scan-matcher and the laser_odometry scheme.

To create a plugin for your scan-matcher (say my_scan_matcher), first create a new ROS package laser_odometry_my_scan_matcher that depends both on laser_odometry_core and your my_scan_matcher.

In this package we then create the wrapper class LaserOdometrMyScanMatcher.

The wrapper has very little requirements, actually a single function is required to be implemented.
However a couple others are available shall you need for instance to initialize your scan matcher on the first scan received or do some post-processing. The overridable functions are detailed below and somewhat summarized in the pseudo-code

The minimal wrapper should be something along the line :

#include <laser_odometry_core/laser_odometry_core.h>
namespace laser_odometry
{

class LaserOdometrMyScanMatcher : public LaserOdometryBase
{
  ...

protected:

  bool process_impl(const sensor_msgs::LaserScanConstPtr& laser_msg,
                    const tf::Transform& prediction) override;
  ...

  MyScanMatcher matcher_;
}

} /* namespace laser_odometry */

Here is a complete detail of each and every overridable functions :

#include <laser_odometry_core/laser_odometry_core.h>
namespace laser_odometry
{

class LaserOdometrMyScanMatcher : public LaserOdometryBase
{
public:

  OdomType odomType() const noexcept override
  {
    // return a laser_odometry::OdomType enum. 
    // Choice is among the following :
    // Unknown   - default
    // Odom2D    - the scan-matcher estimates a 2D odometry
    // Odom2DCov - the scan-matcher estimates a 2D odometry with covariance
    // Odom3D    - the scan-matcher estimates a 3D odometry
    // Odom3DCov - the scan-matcher estimates a 3D odometry with covariance
  }

protected:

  bool process_impl(const sensor_msgs::LaserScanConstPtr& laser_msg,
                    const tf::Transform& prediction) override
  {
    // Derived class **must define this function**

    // This function is the core of the plugin as the main computation takes place here.
    // Given a new reading ' laser_msg ' and the previous key-scan ' reference_scan_ ' 
    // the scan matching should be something along the line :

    correction_ = my_scan_matching(reference_scan_, laser_msg);

    // Where ' correction_ ' is a tf::Transform that contains 
    // the estimated transform in the laser frame.
    // If available, the covariance associated to ' correction_ ' 
    // should be copied to ' twist_covariance_ '

    twist_covariance_ = my_scan_matching_get_covariance();
  }

  // The following functions are available if needed, hence completely optional.
  // They are presented in execution order. The execution order is also recalled
  // in the [[pesudo-code|Overall-execution-pseudo-code]]

  bool configureImpl() override;

  bool initialize(const sensor_msgs::LaserScanConstPtr& scan_msg) override;

  bool isKeyFrame(const tf::Transform& tf) override;
  void isKeyFrame() override;
  void isNotKeyFrame() override;
}

} /* namespace laser_odometry */
Clone this wiki locally