// -*- C++ -*- /*! * @file OccupancyGridMap3D.h * @brief null component * @date $Date$ * * $Id$ */ #ifndef NULL_COMPONENT_H #define NULL_COMPONENT_H #include #include #include "hrpsys/idl/pointcloud.hh" #include #include #include #include #include #include namespace octomap{ class OcTree; }; // Service implementation headers // // // Service Consumer stub headers // // #include "OGMap3DService_impl.h" using namespace RTC; /** \brief sample RT component which has one data input port and one data output port */ class OccupancyGridMap3D : public RTC::DataFlowComponentBase { public: /** \brief Constructor \param manager pointer to the Manager */ OccupancyGridMap3D(RTC::Manager* manager); /** \brief Destructor */ virtual ~OccupancyGridMap3D(); // The initialize action (on CREATED->ALIVE transition) // formaer rtc_init_entry() virtual RTC::ReturnCode_t onInitialize(); // The finalize action (on ALIVE->END transition) // formaer rtc_exiting_entry() // virtual RTC::ReturnCode_t onFinalize(); // The startup action when ExecutionContext startup // former rtc_starting_entry() // virtual RTC::ReturnCode_t onStartup(RTC::UniqueId ec_id); // The shutdown action when ExecutionContext stop // former rtc_stopping_entry() // virtual RTC::ReturnCode_t onShutdown(RTC::UniqueId ec_id); // The activated action (Active state entry action) // former rtc_active_entry() virtual RTC::ReturnCode_t onActivated(RTC::UniqueId ec_id); // The deactivated action (Active state exit action) // former rtc_active_exit() virtual RTC::ReturnCode_t onDeactivated(RTC::UniqueId ec_id); // The execution action that is invoked periodically // former rtc_active_do() virtual RTC::ReturnCode_t onExecute(RTC::UniqueId ec_id); // The aborting action when main logic error occurred. // former rtc_aborting_entry() // virtual RTC::ReturnCode_t onAborting(RTC::UniqueId ec_id); // The error action in ERROR state // former rtc_error_do() // virtual RTC::ReturnCode_t onError(RTC::UniqueId ec_id); // The reset action that is invoked resetting // This is same but different the former rtc_init_entry() // virtual RTC::ReturnCode_t onReset(RTC::UniqueId ec_id); // The state update action that is invoked after onExecute() action // no corresponding operation exists in OpenRTm-aist-0.2.0 // virtual RTC::ReturnCode_t onStateUpdate(RTC::UniqueId ec_id); // The action that is invoked when execution context's rate is changed // no corresponding operation exists in OpenRTm-aist-0.2.0 // virtual RTC::ReturnCode_t onRateChanged(RTC::UniqueId ec_id); OpenHRP::OGMap3D* getOGMap3D(const OpenHRP::AABB& region); void save(const char *filename); void clear(); protected: // Configuration variable declaration // // PointCloudTypes::PointCloud m_cloud; TimedPose3D m_pose; TimedPoint3D m_sensorPos; TimedLong m_update; RangeData m_range; // DataInPort declaration // InPort m_rangeIn; InPort m_cloudIn; InPort m_poseIn; InPort m_sensorPosIn; InPort m_updateIn; // TimedLong m_updateSignal; // DataOutPort declaration // OutPort m_updateOut; // // CORBA Port declaration // RTC::CorbaPort m_OGMap3DServicePort; // // Service declaration // OGMap3DService_impl m_service0; // // Consumer declaration // // private: octomap::OcTree *m_map, *m_knownMap; double m_occupiedThd, m_resolution; std::string m_initialMap; std::string m_knownMapPath; std::string m_cwd; coil::Mutex m_mutex; int m_debugLevel; int dummy; }; extern "C" { void OccupancyGridMap3DInit(RTC::Manager* manager); }; #endif // NULL_COMPONENT_H