git commit -m "first commit for v2"

This commit is contained in:
2025-12-29 16:21:22 +07:00
commit aa3d832d5c
1807 changed files with 307078 additions and 0 deletions

View File

@@ -0,0 +1,43 @@
#ifndef __ABSOLUTE_ENCODER_H_INCLUDED
#define __ABSOLUTE_ENCODER_H_INCLUDED
#include <ros/ros.h>
namespace models
{
class BaseAbsoluteEncoder
{
public:
/**
* @brief Constructs
* @param name The name to give this instance of the model base
*/
virtual void initialize(ros::NodeHandle & nh, const std::string &name) = 0;
/**
* @brief Get the angle of rotation of an axis() rad
*/
virtual double Position() = 0;
/**
* @brief Get the velocity rotation of an axis() rad
*/
virtual double Velocity() = 0;
/**
* @brief Decontructor
*/
virtual ~BaseAbsoluteEncoder() {}
protected:
/**
* @brief Contructor
*/
BaseAbsoluteEncoder() {}
}; // BaseAbsoluteEncoder
} // namespace models
#endif //__ABSOLUTE_ENCODER_H_INCLUDED

View File

@@ -0,0 +1,48 @@
#ifndef __BASE_SENSOR_GROUPS_H_INCLUDED_
#define __BASE_SENSOR_GROUPS_H_INCLUDED_
namespace models
{
enum SensorState
{
Normal,
Warn,
Error,
NotActive,
};
class BaseSensorGroups
{
public:
/**
* @brief Constructs
* @param name The name to give this instance of the model base
*/
virtual void initialize(ros::NodeHandle & nh, const std::string &name) = 0;
/**
* @brief Get state from sensors
*/
virtual models::SensorState State() = 0;
/**
* @brief Get bit logic get from sensor
*/
virtual bool Get() = 0;
/**
* @brief Decontructor
*/
virtual ~BaseSensorGroups() {}
protected:
/**
* @brief Contructor
*/
BaseSensorGroups() {}
}; // class BaseSensorGroups
} // namespace models
#endif

View File

@@ -0,0 +1,105 @@
#ifndef __STEER_DRIVE_H_INCLUDED
#define __STEER_DRIVE_H_INCLUDED
#include <ros/ros.h>
namespace models
{
class BaseSteerDrive
{
public:
/**
* @brief Constructs
* @param name The name to give this instance of the model base
*/
virtual void initialize(ros::NodeHandle & nh, const std::string &name) = 0;
/**
* @brief Constructs
* @param name Check model is deady
* @return true, if model is ready, false otherwise
*/
virtual bool Ready() {return true;}
/**
* @brief Get the velocity limit on axis(index).
* @return Velocity limit specified in SDF
*/
virtual double GetVelocityLimit(unsigned int _index) = 0;
/**
* @brief Set the velocity limit on a joint axis.
* @param[in] _velocity Velocity limit for the axis.
*/
virtual void SetVelocityLimit(double _velocity) = 0;
/**
* @brief Get the rotation rate of an axis(index)
* @return The rotaional velocity of the joint axis.
*/
virtual double GetVelocity() = 0;
/**
* @brief Set the velocity of an axis(index).
* In ODE and Bullet, the SetVelocityMaximal function is used to
* set the velocity of the child link relative to the parent.
* In Simbody and DART, this function updates the velocity state,
* which has a recursive effect on the rest of the chain.
* @param[in] _vel Velocity.
*/
virtual void SetVelocity(double _vel) = 0;
/**
* @brief Get the position of an axis according to its index.
*
* For rotational axes, the value is in radians. For prismatic axes,
* it is in meters.
*
* For static models, it returns the static joint position.
*
* It returns ignition::math::NAN_D in case the position can't be
* obtained. For instance, if the index is invalid, if the joint is
* fixed, etc.
*
* Subclasses can't override this method. See PositionImpl instead.
*
* @return Current position of the axis.
* @sa PositionImpl
*/
virtual double Position() = 0;
/**
* @brief The child links of this joint are updated based on desired
* position. And all the links connected to the child link of this joint
* except through the parent link of this joint moves with the child
* link.
* @param[in] _position Position to set the joint to.
* unspecified, pure kinematic teleportation.
* link with respect to the world frame will remain the same after
* setting the position. By default this is false, which means there are
* no guarantees about what the child link's world velocity will be after
* the position is changed (the behavior is determined by the underlying
* physics engine).
*
* @note{Only ODE and Bullet support _preserveWorldVelocity being true.}
*/
virtual void SetPosition(const double _position) = 0;
/**
* @brief Decontructor
*/
virtual ~BaseSteerDrive() {}
protected:
/**
* @brief Contructor
*/
BaseSteerDrive() {}
}; // class BaseSteerDrive
} // namespace models
#endif // __STEER_DRIVE_H_INCLUDED

View File

@@ -0,0 +1,53 @@
#ifndef __MODELS_TYPES_H_INCLUDED
#define __MODELS_TYPES_H_INCLUDED
#include <vector>
#include <boost/shared_ptr.hpp>
/**
* @brief models forward declarations and type defines
*/
namespace models
{
class BaseSteerDrive;
class BaseAbsoluteEncoder;
class BaseSensorGroups;
/**
* @def BaseSteerDrivePtr
* @brief Boost shared pointer to a BaseSteerDrive object
*/
typedef boost::shared_ptr<BaseSteerDrive> BaseSteerDrivePtr;
/**
* @def BaseAbsoluteEncoderPtr
* @brief Boost shared pointer to a BaseAbsoluteEncoder object
*/
typedef boost::shared_ptr<BaseAbsoluteEncoder> BaseAbsoluteEncoderPtr;
/**
* @def BaseSensorGroupsPtr
* @brief Boost shared pointer to a BaseSensorGroups object
*/
typedef boost::shared_ptr<BaseSensorGroups> BaseSensorGroupsPtr;
/**
* @def BaseSteerDrive_V
* @brief Vector of BaseSteerDrivePtr
*/
typedef std::vector<BaseSteerDrivePtr> BaseSteerDrive_V;
/**
* @def BaseAbsoluteEncoder_V
* @brief Vector of BaseAbsoluteEncoderPtr
*/
typedef std::vector<BaseAbsoluteEncoderPtr> BaseAbsoluteEncoder_V;
/**
* @def BaseSensorGroups_V
* @brief Vector of BaseSensorGroupsPtr
*/
typedef std::vector<BaseSensorGroupsPtr> BaseSensorGroups_V;
} // namespace models
#endif // MODELS_TYPES_H_INCLUDED