A tick-tock release cycle allows easy migration to new software versions. Obsolete Gazebo code is marked as deprecated for one major release. Deprecated code produces compile-time warnings. These warning serve as notification to users that their code should be upgraded. The next major release will remove the deprecated code.
-
gazebo/physics/ode/ODEJoint.hh
- public: virtual void Fini();
-
gazebo/physics/bullet/BulletJoint.hh
- public: virtual void Fini();
-
gazebo/physics/Model.hh
- public: gazebo::physics::JointPtr CreateJoint( const std::string &_name, const std::string &_type, physics::LinkPtr _parent, physics::LinkPtr _child);
- public: bool RemoveJoint(const std::string &_name);
- public: boost::shared_ptr shared_from_this();
-
gazebo/physics/SurfaceParams.hh
- public: double PoissonsRatio() const;
- public: void SetPoissonsRatio(double _ratio);
- public: double ElasticModulus() const;
- public: void SetElasticModulus(double _modulus);
-
gazebo/sensor/SensorTypes.hh
- All
typedef
's ofshared_ptr
's to Sensor's are changed fromboost::shared_ptr
tostd::shared_ptr
. Any downstream code that does a pointer cast (such asdynamic_pointer_cast
orstatic_pointer_cast
) will need to switch fromboost::*_pointer_cast
tostd::*_pointer_cast
. - pull request #2079
- All
-
gazebo/sensors/Sensor.hh
- Removed: public: template event::ConnectionPtr ConnectUpdated(T _subscriber);
- Replacement: public: event::ConnectionPtr ConnectUpdated(std::function<void()> _subscriber);
-
gazebo/rendering/GpuLaser.hh
- Removed: public: void SetCameraCount(double _cameraCount);
- Replacement: public: void SetCameraCount(const unsigned int _cameraCount);
- Removed: public: template event::ConnectionPtr ConnectNewLaserFrame(T _subscriber);
- Replacement: public: event::ConnectionPtr ConnectNewLaserFrame(std::function<void (const float *_frame, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)> _subscriber);
-
gazebo/rendering/DepthCamera.hh
- Removed: public: template event::ConnectionPtr ConnectNewDepthFrame(T _subscriber)
- Replacement: public: event::ConnectionPtr ConnectNewDepthFrame(std::function<void (const float *, unsigned int, unsigned int, unsigned int, const std::string &)> _subscriber);
- Removed: public: template event::ConnectionPtr ConnectNewRGBPointCloud(T _subscriber)
- Replacement: public: event::ConnectionPtr ConnectNewRGBPointCloud(std::function<void (const float *, unsigned int, unsigned int, unsigned int, const std::string &)> _subscriber);
-
gazebo/physics/Actor.hh
- Type change of
protected: math::Vector3 lastPos;
toprotected: ignition::math::Vector3d lastPos;
- Type change of
-
gazebo/rendering/RenderTypes.hh
- typedefs for Visual and its derived classes have been changed from boost to std pointers.
- pull request #1924
-
gazebo/gui/model/ModelEditorEvents.hh
- Removed: public: static event::EventT<void (bool, bool, const math::Pose &, const std::string &)> modelPropertiesChanged
- Replacement: public: static event::EventT<void (bool, bool)> modelPropertiesChanged
- Note: Removed last two arguments, model pose and name, from the function
-
gazebo/rendering/Camera.hh
- Removed: public: void SetClipDist();
- Replacement: public: virtual void SetClipDist();
- Removed: public: template event::ConnectionPtr ConnectNewImageFrame(T _subscriber);
- Replacement: public: event::ConnectionPtr ConnectNewImageFrame(std::function<void (const unsigned char *, unsigned int, unsigned int, unsigned int, const std::string &)> _subscriber);
-
gazebo/msgs/logical_camera_sensors.proto
- The
near
andfar
members have been replaced withnear_clip
andfar_clip
- Pull request #1942
- The
-
Light topic
- Removed: ~/light
- Replacement: ~/factory/light - for spawning new lights
- Replacement: ~/light/modify - for modifying existing lights
-
gazebo/rendering/Visual.hh
- Removed: public: void SetVisible(bool _visible, bool _cascade = true);
- Replacement: public: virtual void SetVisible(bool _visible, bool _cascade = true);
-
gazebo/rendering/OribitViewController.hh
- Removed: public: OrbitViewController(UserCameraPtr _camera);
- Replacement: public: OrbitViewController(UserCameraPtr _camera, const std::string &_name = "OrbitViewController");
-
gazebo/test/ServerFixture.hh
- Removed: protected: void RunServer(const std::string &_worldFilename);
- Removed: protected: void RunServer(const std::string &_worldFilename, bool _paused, const std::string &_physics, const std::vectorstd::string & _systemPlugins = {});
- Replacement: void ServerFixture::RunServer(const std::vector<:string> &_args)
-
gazebo/gui/building/BuildingMaker.hh
- Doesn't inherit from gui::EntityMaker anymore
- Pull request #1828
-
gazebo/gui/EntityMaker.hh
- Removed: EntityMaker();
- Replacement: EntityMaker(EntityMakerPrivate &_dataPtr);
- Removed: public: virtual void Start(const rendering::UserCameraPtr _camera) = 0;
- Replacement: public: virtual void Start();
- Removed: public: virtual void Stop() = 0;
- Replacement: public: virtual void Stop();
-
gazebo/gui/ModelAlign.hh
- Removed: public: void AlignVisuals(std::vectorrendering::VisualPtr _visuals, const std::string &_axis, const std::string &_config, const std::string &_target, bool _publish = true);
- Replacement: public: void AlignVisuals(std::vectorrendering::VisualPtr _visuals, const std::string &_axis, const std::string &_config, const std::string &_target, bool _publish = true, const bool _inverted = false);
-
gazebo/gui/GuiEvents.hh
- Removed: public: static event::EventT<void (std::string, std::string, std::string, bool)> alignMode; std::string, std::string, bool)> alignMode;
- Replacement: public: static event::EventT<void (std::string, std::string, std::string, bool)> alignMode; std::string, std::string, bool, bool)> alignMode;
-
gazebo/util/OpenAL.hh
- Deprecation: public: bool GetOnContact() const;
- Replacement: public: bool OnContact() const;
- Deprecation: public: std::vectorstd::string GetCollisionNames() const;
- Replacement: public: std::vectorstd::string CollisionNames() const;
-
gazebo/util/LogRecord.hh
- Deprecation: public: bool GetPaused() const;
- Replacement: public: bool Paused() const;
- Deprecation: public: bool GetRunning() const;
- Replacement: public: bool Running() const;
- Deprecation: public: const std::string &GetEncoding() const;
- Replacement: public: const std::string &Encoding() const;
- Deprecation: public: std::string GetFilename(const std::string &_name = "") const;
- Replacement: public: std::string Filename(const std::string &_name = "") const;
- Deprecation: public: unsigned int GetFileSize(const std::string &_name = "") const
- Replacement: public: unsigned int FileSize(const std::string &_name = "") const;
- Deprecation: public: std::string GetBasePath() const;
- Replacement: public: std::string BasePath() const;
- Deprecation: public: common::Time GetRunTime() const;
- Replacement: public: common::Time RunTime() const;
- Deprecation: public: bool GetFirstUpdate() const;
- Replacement: public: bool FirstUpdate() const;
- Deprecation: public: unsigned int GetBufferSize() const;
- Replacement: public: unsigned int BufferSize() const;
-
gazebo/rendering/Scene.hh
- Deprecation: public: Ogre::SceneManager *GetManager() const;
- Replacement: public: Ogre::SceneManager *OgreSceneManager() const;
- Deprecation: public: std::string GetName() const;
- Replacement: public: std::string Name() const;
- Deprecation: public: common::Color GetAmbientColor() const;
- Replacement: public: common::Color AmbientColor() const;
- Deprecation: public: common::Color GetBackgroundColor();
- Replacement: public: common::Color BackgroundColor() const;
- Deprecation: public: uint32_t GetGridCount();
- Replacement: public: uint32_t GridCount() const;
- Deprecation: public: uint32_t GetOculusCameraCount() const;
- Replacement: public: uint32_t OculusCameraCount() const;
- Deprecation: public: uint32_t GetCameraCount() const;
- Replacement: public: uint32_t CameraCount() const;
- Deprecation: public: uint32_t GetUserCameraCount() const;
- Replacement: public: uint32_t UserCameraCount() const;
- Deprecation: public: uint32_t GetLightCount() const;
- Replacement: public: uint32_t LightCount() const;
- Deprecation: public: VisualPtr GetVisualAt(CameraPtr _camera, const math::Vector2i &_mousePos, std::string &_mod)
- Replacement: public: VisualPtr VisualAt(CameraPtr _camera, const ignition::math::Vector2i &_mousePos, std::string &_mod);
- Deprecation: public: VisualPtr GetVisualAt(CameraPtr _camera, const math::Vector2i &_mousePos)
- Replacement: public: VisualPtr VisualAt(CameraPtr _camera, const ignition::math::Vector2i &_mousePos);
- Deprecation: public: VisualPtr GetVisualBelow(const std::string &_visualName);
- Replacement: public: VisualPtr VisualBelow(const std::string &_visualName);
- Deprecation: public: void GetVisualsBelowPoint(const math::Vector3 &_pt, std::vector &_visuals);
- Replacement: public: void VisualsBelowPoint(const ignition::math::Vector3d &_pt, std::vector &_visuals);
- Deprecation: public: double GetHeightBelowPoint(const math::Vector3 &_pt);
- Replacement: public: double HeightBelowPoint(const ignition::math::Vector3d &_pt);
- Deprecation: public: bool GetFirstContact(CameraPtr _camera, const math::Vector2i &_mousePos, math::Vector3 &_position)
- Replacement: public: bool FirstContact(CameraPtr _camera, const ignition::math::Vector2i &_mousePos, ignition::math::Vector3d &_position);
- Deprecation: public: void DrawLine(const math::Vector3 &_start, const math::Vector3 &_end, const std::string &_name)
- Replacement: public: void DrawLine(const ignition::math::Vector3d &_start, const ignition::math::Vector3d &_end, const std::string &_name);
- Deprecation: public: uint32_t GetId() const;
- Replacement: public: uint32_t Id() const;
- Deprecation: public: std::string GetIdString() const;
- Replacement: public: std::string IdString() const;
- Deprecation: public: bool GetShadowsEnabled() const;
- Replacement: public: bool ShadowsEnabled() const;
- Deprecation: public: VisualPtr GetWorldVisual() const;
- Replacement: public: VisualPtr WorldVisual() const;
- Deprecation: public: VisualPtr GetSelectedVisual() const;
- Replacement: public: VisualPtr SelectedVisual() const;
- Deprecation: public: bool GetShowClouds() const;
- Replacement: public: bool ShowClouds() const;
- Deprecation: public: bool GetInitialized() const;
- Replacement: public: bool Initialized() const;
- Deprecation: public: common::Time GetSimTime() const;
- Replacement: public: common::Time SimTime() const;
- Deprecation: public: uint32_t GetVisualCount() const
- Replacement: public: uint32_t VisualCount() const;
-
gazebo/rendering/DepthCamera.hh
- Deprecation: public: virtual const float *GetDepthData();
- Replacement: public: virtual const float *DepthData() const;
-
gazebo/rendering/Heightmap.hh
- Deprecation: public: double GetHeight(double _x, double _y, double _z = 1000);
- Replacement: public: double Height(const double _x, const double _y, const double _z = 1000) const;
- Deprecation: public: bool Flatten(CameraPtr _camera, math::Vector2i _mousePos, double _outsideRadius, double _insideRadius, double _weight = 0.1)
- Replacement: public: bool Flatten(CameraPtr _camera, const ignition::math::Vector2i &_mousePos, const double _outsideRadius, const double _insideRadius, const double _weight = 0.1);
- Deprecation: public: bool Smooth(CameraPtr _camera, math::Vector2i _mousePos, double _outsideRadius, double _insideRadius, double _weight = 0.1);
- Replacement: public: bool Smooth(CameraPtr _camera, const ignition::math::Vector2i &_mousePos, const double _outsideRadius, const double _insideRadius, const double _weight = 0.1);
- Deprecation: public: bool Raise(CameraPtr _camera, math::Vector2i _mousePos, double _outsideRadius, double _insideRadius, double _weight = 0.1)
- Replacement: public: bool Raise(CameraPtr _camera, const ignition::math::Vector2i &_mousePos, const double _outsideRadius, const double _insideRadius, const double _weight = 0.1)
- Deprecation: public: bool Lower(CameraPtr _camera, math::Vector2i _mousePos, double _outsideRadius, double _insideRadius, double _weight = 0.1)
- Replacement: public: bool Lower(CameraPtr _camera, const ignition::math::Vector2i &_mousePos, const double _outsideRadius, const double _insideRadius, const double _weight = 0.1)
- Deprecation: public: double GetAvgHeight(Ogre::Vector3 _pos, double _brushSize);
- Replacement: public: double AvgHeight(const ignition::math::Vector3d &_pos, const double _brushSize) const
- Deprecation: public: Ogre::TerrainGroup *GetOgreTerrain() const;
- Replacement: public: Ogre::TerrainGroup *OgreTerrain() const;
- Deprecation: public: common::Image GetImage() const;
- Replacement: public: public: common::Image Image() const;
- Deprecation: public: Ogre::TerrainGroup::RayResult GetMouseHit(CameraPtr _camera, math::Vector2i _mousePos);
- Replacement: public: Ogre::TerrainGroup::RayResult MouseHit(CameraPtr _camera, const ignition::math::Vector2i &_mousePos) const;
- Deprecation: public: unsigned int GetTerrainSubdivisionCount() const;
- Replacement: public: unsigned int TerrainSubdivisionCount() const;
-
gazebo/rendering/RenderEngine.hh
- Deprecation: public: unsigned int GetSceneCount() const;
- Replacement: public: unsigned int SceneCount() const;
- Deprecation: public: Ogre::OverlaySystem *GetOverlaySystem() const;
- Replacement: public: Ogre::OverlaySystem *OverlaySystem() const;
-
gazebo/rendering/GpuLaser.hh
- Deprecation: public: const float *GetLaserData();
- Replacement: public: const float *LaserData() const;
- Deprecation: public: double GetHorzHalfAngle() const;
- Replacement: public: double HorzHalfAngle() const;
- Deprecation: public: double GetVertHalfAngle() const;
- Replacement: public: double VertHalfAngle() const;
- Deprecation: public: double GetHorzFOV() const;
- Replacement: public: double HorzFOV() const;
- Deprecation: public: double GetCosHorzFOV() const;
- Replacement: public: double CosHorzFOV() const;
- Deprecation: public: double GetVertFOV() const;
- Replacement: public: double VertFOV() const;
- Deprecation: public: double GetCosVertFOV() const;
- Replacement: public: double CosVertFOV() const;
- Deprecation: public: double GetNearClip() const;
- Replacement: public: double NearClip() const;
- Deprecation: public: double GetFarClip() const;
- Replacement: public: double FarClip() const;
- Deprecation: public: double CameraCount() const;
- Replacement: public: unsigned int CameraCount() const;
- Deprecation: public: double GetRayCountRatio() const;
- Replacement: public: double RayCountRatio() const;
-
gazebo/rendering/DynamicLines.hh
- Deprecation: public: void AddPoint(const math::Vector3 &_pt,const common::Color &_color = common::Color::White)
- Replacement: public: void AddPoint(const ignition::math::Vector3d &_pt,const common::Color &_color = common::Color::White);
- Deprecation: public: void SetPoint(unsigned int _index, const math::Vector3 &_value)
- Replacement: public: void SetPoint(unsigned int _index,const ignition::math::Vector3d &_value);
- Deprecation: public: math::Vector3 GetPoint(unsigned int _index) const
- Replacement: public: ignition::math::Vector3d Point(const unsigned int _index) const;
-
gazebo/rendering/WindowManager.hh
- Deprecation: public: uint32_t GetAvgFPS(uint32_t _id);
- Replacement: public: uint32_t AvgFPS(const uint32_t _id) const;
- Deprecation: public: uint32_t GetTriangleCount(uint32_t _id);
- Replacement: public: uint32_t TriangleCount(const uint32_t _id) const;
- Deprecation: public: Ogre::RenderWindow *GetWindow(uint32_t _id);
- Replacement: public: Ogre::RenderWindow *Window(const uint32_t _id) const;
-
gazebo/rendering/Light.hh
- Deprecation: public: std::string GetName() const;
- Replacement: public: std::string Name() const;
- Deprecation: public: std::string GetType() const;
- Replacement: public: std::string Type() const;
- Deprecation: public: public: void SetPosition(const math::Vector3 &_p);
- Replacement: public: void SetPosition(const ignition::math::Vector3d &_p);
- Deprecation: public: math::Vector3 GetPosition();
- Replacement: public: ignition::math::Vector3d Position() const;
- Deprecation: public: void SetRotation(const math::Quaternion &_q);
- Replacement: public: void SetRotation(const ignition::math::Quaterniond &_q);
- Deprecation: public: math::Quaternion GetRotation() const;
- Replacement: public: ignition::math::Quaterniond Rotation() const;
- Deprecation: public: bool GetVisible() const;
- Replacement: public: bool Visible() const;
- Deprecation: public: common::Color GetDiffuseColor() const;
- Replacement: public: common::Color DiffuseColor() const;
- Deprecation: public: common::Color GetSpecularColor() const;
- Replacement: public: common::Color SpecularColor() const;
- Deprecation: public: void SetDirection(const math::Vector3 &_dir);
- Replacement: public: void SetDirection(const ignition::math::Vector3d &_dir);
- Deprecation: public: math::Vector3 GetDirection() const;
- Replacement: public: ignition::math::Vector3d Direction() const;
-
gazebo/util/Diagnostics.hh
- Deprecation: public: int GetTimerCount() const;
- Replacement: public: int TimerCount() const;
- Deprecation: public: common::Time GetTime(int _index) const;
- Replacement: public: common::Time Time(const int _index) const;
- Deprecation: public: common::Time GetTime(const std::string &_label) const;
- Replacement: public: common::Time Time(const std::string &_label) const;
- Deprecation: public: std::string GetLabel(int _index) const;
- Replacement: public: std::string Label(const int _index) const;
- Deprecation: public: boost::filesystem::path GetLogPath() const
- Replacement: public: boost::filesystem::path LogPath() const;
-
gazebo/sensors/CameraSensor.hh
- *Deprecation: public: virtual std::string GetTopic() const;
- *Replacement: public: virtual std::string Topic() const;
- *Deprecation: public: rendering::CameraPtr GetCamera() const
- *Replacement: public: rendering::CameraPtr Camera() const;
- *Deprecation: public: unsigned int GetImageWidth() const;
- *Replacement: public: unsigned int ImageWidth() const;
- *Deprecation: public: unsigned int GetImageHeight() const;
- *Replacement: public: unsigned int ImageHeight() const;
- *Deprecation: public: const unsigned char *GetImageData();
- *Replacement: const unsigned char *ImageData() const;
-
gazebo/util/LogPlay.hh
- Deprecation: public: std::string GetLogVersion() const;
- Replacement: public: std::string LogVersion() const;
- Deprecation: public: std::string GetGazeboVersion() const;
- Replacement: public: std::string GazeboVersion() const;
- Deprecation: public: uint32_t GetRandSeed() const
- Replacement: public: uint32_t RandSeed() const;
- Deprecation: public: common::Time GetLogStartTime() const;
- Replacement: public: common::Time LogStartTime() const;
- Deprecation: public: common::Time GetLogEndTime() const;
- Replacement: public: common::Time LogEndTime() const;
- Deprecation: public: std::string GetFilename() const;
- Replacement: public: std::string Filename() const;
- Deprecation: public: std::string GetFullPathFilename() const;
- Replacement: public: std::string FullPathFilename() const;
- Deprecation: public: uintmax_t GetFileSize() const
- Replacement: public: uintmax_t FileSize() const;
- Deprecation: public: unsigned int GetChunkCount() const;
- Replacement: public: unsigned int ChunkCount() const;
- Deprecation: public: bool GetChunk(unsigned int _index, std::string &_data);
- Replacement: public: bool Chunk(const unsigned int _index, std::string &_data) const;
- Deprecation: public: std::string GetEncoding() const
- Replacement: public: std::string Encoding() const;
- Deprecation: public: std::string GetHeader() const
- Replacement: public: std::string Header() const;
- Deprecation: public: uint64_t GetInitialIterations() const
- Replacement: public: uint64_t InitialIterations() const;
-
gazebo/sensors/ContactSensor.hh
- *Deprecation: public: msgs::Contacts GetContacts() const;
- *Replacement: public: msgs::Contacts Contacts() const;
- *Deprecation: public: std::map<std::string, physics::Contact> GetContacts(const std::string &_collisionName);
- *Replacement: public: std::map<std::string, physics::Contact> Contacts(const std::string &_collisionName) const;
-
gazebo/sensors/DepthCameraSensor.hh
- *Deprecation: public: rendering::DepthCameraPtr GetDepthCamera() const
- *Replacement: public: rendering::DepthCameraPtr DepthCamera() const;
-
gazebo/sensors/ForceTorqueSensor.hh
- *Deprecation: public: virtual std::string GetTopic() const
- *Replacement: public: virtual std::string Topic() const;
- *Deprecation: public: physics::JointPtr GetJoint() const;
- *Replacement: public: physics::JointPtr Joint() const;
-
gazebo/sensors/GpsSensor.hh
- *Deprecation: public: double GetAltitude();
- *Replacement: public: double Altitude() const;
-
gazebo/sensors/GpuRaySensor.hh
- *Deprecation: public: virtual std::string GetTopic() const;
- *Replacement: public: virtual std::string Topic() const;
- *Deprecation: public: rendering::GpuLaserPtr GetLaserCamera() const
- *Replacement: public: rendering::GpuLaserPtr LaserCamera() const;
- *Deprecation: public: double GetAngleResolution() const
- *Replacement: public: double AngleResolution() const;
- *Deprecation: public: double GetRangeMin() const
- *Replacement: public: double RangeMin() const;
- *Deprecation: public: double GetRangeMax() const
- *Replacement: public: double RangeMax() const;
- *Deprecation: public: double GetRangeResolution() const
- *Replacement: public: double RangeResolution() const;
- *Deprecation: public: int GetRayCount() const
- *Replacement: public: int RayCount() const;
- *Deprecation: public: int GetRangeCount() const
- *Replacement: public: int RangeCount() const;
- *Deprecation: public: int GetVerticalRayCount() const
- *Replacement: public: int VerticalRayCount()
- *Deprecation: public: int GetVerticalRangeCount() const;
- *Replacement: public: int VerticalRangeCount() const;
- *Deprecation: public: double GetVerticalAngleResolution() const
- *Replacement: public: double VerticalAngleResolution() const;
- *Deprecation: public: double GetRange(int _index)
- *Replacement: public: double Range(const int _index) const;
- *Deprecation: public: void GetRanges(std::vector &_ranges)
- *Replacement: public: void Ranges(std::vector &_ranges) const
- *Deprecation: public: double GetRetro(int _index) const
- *Replacement: public: double Retro(const int _index) const;
- *Deprecation: public: int GetFiducial(int _index) const
- *Replacement: public: int Fiducial(const unsigned int _index) const;
- *Deprecation: public: unsigned int GetCameraCount() const
- *Replacement: public: unsigned int CameraCount() const;
- *Deprecation: public: double GetRayCountRatio()
- *Replacement: public: double RayCountRatio() const;
- *Deprecation: public: double GetRangeCountRatio() const
- *Replacement: public: double RangeCountRatio() const;
- *Deprecation: public: double GetHorzFOV() const
- *Replacement: public: double HorzFOV() const;
- *Deprecation: public: double GetCosHorzFOV() const
- *Replacement: public: double CosHorzFOV() const;
- *Deprecation: public: double GetVertFOV() const
- *Replacement: public: double VertFOV() const;
- *Deprecation: public: double GetCosVertFOV() const
- *Replacement: public: double CosVertFOV() const;
- *Deprecation: public: double GetHorzHalfAngle() const
- *Replacement: public: double HorzHalfAngle() const;
- *Deprecation: public: double GetVertHalfAngle() const
- *Replacement: public: double VertHalfAngle() const;
-
gazebo/sensors/ImuSensor.hh
- *Deprecation: public: msgs::IMU GetImuMessage() const
- *Replacement: public: msgs::IMU ImuMessage() const;
-
gazebo/sensors/MultiCameraSensor.hh
- *Deprecation: public: virtual std::string GetTopic() const;
- *Replacement: public: virtual std::string Topic() const;
- *Deprecation: public: unsigned int GetCameraCount() const
- *Replacement: public: unsigned int CameraCount() const;
- *Deprecation: public: rendering::CameraPtr GetCamera(unsigned int _index) const
- *Replacement: public: rendering::CameraPtr Camera(const unsigned int _index) const;
- *Deprecation: public: unsigned int GetImageWidth(unsigned int _index) const
- *Replacement: public: unsigned int ImageWidth(const unsigned int _index) const;
- *Deprecation: public: unsigned int GetImageHeight(unsigned int _index) const
- *Replacement: public: unsigned int ImageHeight(const unsigned int _index) const;
- *Deprecation: public: const unsigned char *GetImageData(unsigned int _index)
- *Replacement: public: const unsigned char *ImageData(const unsigned int _index);
-
gazebo/sensors/RaySensor.hh
- *Deprecation: public: virtual std::string GetTopic() const;
- *Replacement: public: virtual std::string Topic() const;
- *Deprecation: public: double GetAngleResolution() const
- *Replacement: public: double AngleResolution() const;
- *Deprecation: public: double GetRangeMin() const
- *Replacement: public: double RangeMin() const;
- *Deprecation: public: double GetRangeMax() const
- *Replacement: public: double RangeMax() const;
- *Deprecation: public: double GetRangeResolution() const
- *Replacement: public: double RangeResolution() const;
- *Deprecation: public: int GetRayCount() const
- *Replacement: public: int RayCount() const;
- *Deprecation: public: int GetRangeCount() const
- *Replacement: public: int RangeCount() const;
- *Deprecation: public: int GetVerticalRayCount() const
- *Replacement: public: int VerticalRayCount() const
- *Deprecation: public: int GetVerticalRangeCount() const
- *Replacement: public: int VerticalRangeCount() const;
- *Deprecation: public: double GetVerticalAngleResolution() const
- *Replacement: public: double VerticalAngleResolution() const;
- *Deprecation: public: double GetRange(unsigned int _index)
- *Replacement: public: double Range(const unsigned int _index) const;
- *Deprecation: public: void GetRanges(std::vector &_ranges)
- *Replacement: public: void Ranges(std::vector &_ranges) const;
- *Deprecation: public: double GetRetro(unsigned int _index)
- *Replacement: public: double Retro(const unsigned int _index) const;
- *Deprecation: public: int GetFiducial(unsigned int _index)
- *Replacement: public: int Fiducial(const unsigned int _index) const;
- *Deprecation: public: physics::MultiRayShapePtr GetLaserShape()
- *Replacement: public: physics::MultiRayShapePtr LaserShape() const;
-
gazebo/sensors/Sensor.hh
- *Deprecation: public: std::string GetParentName() const
- *Replacement: public: std::string ParentName() const;
- *Deprecation: public: double GetUpdateRate()
- *Replacement: public: double UpdateRate() const;
- *Deprecation: public: std::string GetName() const
- *Replacement: public: std::string Name() const;
- *Deprecation: public: std::string GetScopedName() const
- *Replacement: public: std::string ScopedName() const;
- *Deprecation: public: std::string GetType() const
- *Replacement: public: std::string Type() const;
- *Deprecation: public: common::Time GetLastUpdateTime()
- *Replacement: public: common::Time LastUpdateTime() const;
- *Deprecation: public: common::Time GetLastMeasurementTime()
- *Replacement: public: common::Time LastMeasurementTime() const;
- *Deprecation: public: bool GetVisualize() const
- *Replacement: public: bool Visualize() const;
- *Deprecation: public: virtual std::string GetTopic() const
- *Replacement: public: virtual std::string Topic() const;
- *Deprecation: public: std::string GetWorldName() const
- *Replacement: public: std::string WorldName() const;
- *Deprecation: public: SensorCategory GetCategory() const
- *Replacement: public: SensorCategory Category() const;
- *Deprecation: public: uint32_t GetId() const
- *Replacement: public: uint32_t Id() const;
- *Deprecation: public: uint32_t GetParentId() const
- *Replacement: public: uint32_t ParentId() const;
- *Deprecation: public: NoisePtr GetNoise(const SensorNoiseType _type) const
- *Replacement: public: NoisePtr Noise(const SensorNoiseType _type) const;
-
gazebo/sensors/SonarSensor.hh
- *Deprecation: public: virtual std::string GetTopic() const;
- *Replacement: public: virtual std::string Topic() const;
- *Deprecation: public: double GetRangeMin() const
- *Replacement: public: double RangeMin() const;
- *Deprecation: public: double GetRangeMax() const
- *Replacement: public: double RangeMax() const;
- *Deprecation: public: double GetRadius() const
- *Replacement: public: double Radius() const;
- *Deprecation: public: double GetRange()
- *Replacement: public: double Range();
-
gazebo/sensors/WirelessReceiver.hh
- *Deprecation: public: double GetMinFreqFiltered() const
- *Replacement: public: double MinFreqFiltered() const;
- *Deprecation: public: double GetMaxFreqFiltered() const
- *Replacement: public: double MaxFreqFiltered() const;
- *Deprecation: public: double GetSensitivity() const
- *Replacement: public: double Sensitivity() const;
-
gazebo/sensors/WirelessTransceiver.hh
- *Deprecation: public: virtual std::string GetTopic() const;
- *Replacement: public: virtual std::string Topic() const;
- *Deprecation: public: double GetGain() const
- *Replacement: public: double Gain() const;
- *Deprecation: public: double GetPower() const
- *Replacement: public: double Power() const;
-
gazebo/sensors/WirelessTransmitter.hh
- *Deprecation: public: std::string GetESSID() const
- *Replacement: public: std::string ESSID() const;
- *Deprecation: public: double GetFreq() const
- *Replacement: public: double Freq() const;
-
gazebo/rendering/ApplyWrenchVisual.hh
- Deprecation: public: void SetCoM(const math::Vector3 &_comVector)
- Replacement: public: void SetCoM(const ignition::math::Vector3d &_comVector);
- Deprecation: public: void SetForcePos(const math::Vector3 &_forcePosVector)
- Replacement: public: void SetForcePos(const ignition::math::Vector3d &_forcePosVector);
- Deprecation: public: void SetForce(const math::Vector3 &_forceVector,const bool _rotatedByMouse);
- Replacement: public: void SetForce(const ignition::math::Vector3d &_forceVector, const bool _rotatedByMouse);
- Deprecation: public: void SetTorque(const math::Vector3 &_torqueVector,const bool _rotatedByMouse);
- Replacement: public: void SetTorque(const ignition::math::Vector3d &_torqueVector, const bool _rotatedByMouse);
-
gazebo/rendering/AxisVisual.hh
- Deprecation: public: void ScaleXAxis(const math::Vector3 &_scale)
- Replacement: public: void ScaleXAxis(const ignition::math::Vector3d &_scale);
- Deprecation: public: void ScaleYAxis(const math::Vector3 &_scale)
- Replacement: public: void ScaleYAxis(const ignition::math::Vector3d &_scale);
- Deprecation: public: void ScaleZAxis(const math::Vector3 &_scale)
- Replacement: public: void ScaleZAxis(const ignition::math::Vector3d &_scale);
-
gazebo/gui/CloneWindow.hh
- Deprecation: int GetPort()
- Replacement: int Port() const
-
gazebo/gui/ConfigWidget.hh
- Deprecation: public: google::protobuf::Message *GetMsg()
- Replacement: public: google::protobuf::Message *Msg()
- Deprecation: public: std::string GetHumanReadableKey(const std::string &_key)
- Replacement: public: std::string HumanReadableKey(const std::string &_key) const
- Deprecation: public: std::string GetUnitFromKey(const std::string &_key, const std::string &_jointType = "")
- Replacement: public: std::string UnitFromKey(const std::string &_key, const std::string &_jointType = "") const
- Deprecation: public: void GetRangeFromKey(const std::string &_key, double &_min, double &_max)
- Replacement: public: void RangeFromKey(const std::string &_key, double &_min, double &_max) const
- Deprecation: public: bool GetWidgetVisible(const std::string &_name)
- Replacement: public: bool WidgetVisible(const std::string &_name) const
- Deprecation: public: bool GetWidgetReadOnly(const std::string &_name) const
- Replacement: public: bool WidgetReadOnly(const std::string &_name) const
- Deprecation: public: bool SetVector3WidgetValue(const std::string &_name, const math::Vector3 &_value)
- Replacement: public: bool SetVector3dWidgetValue(const std::string &_name, const ignition::math::Vector3d &_value)
- Deprecation: public: bool SetPoseWidgetValue(const std::string &_name, const math::Pose &_value)
- Replacement: public: bool SetPoseWidgetValue(const std::string &_name, const ignition::math::Pose3d &_value)
- Deprecation: public: bool SetGeometryWidgetValue(const std::string &_name, const std::string &_value, const math::Vector3 &_dimensions, const std::string &_uri = "")
- Replacement: public: bool SetGeometryWidgetValue(const std::string &_name, const std::string &_value, const ignition::math::Vector3d &_dimensions, const std::string &_uri = "")
- Deprecation: public: int GetIntWidgetValue(const std::string &_name) const
- Replacement: public: int IntWidgetValue(const std::string &_name) const
- Deprecation: public: unsigned int GetUIntWidgetValue(const std::string &_name) const
- Replacement: public: unsigned int UIntWidgetValue(const std::string &_name) const
- Deprecation: public: double GetDoubleWidgetValue(const std::string &_name) const
- Replacement: public: double DoubleWidgetValue(const std::string &_name) const
- Deprecation: public: bool GetBoolWidgetValue(const std::string &_name) const
- Replacement: public: bool BoolWidgetValue(const std::string &_name) const
- Deprecation: public: std::string GetStringWidgetValue(const std::string &_name) const
- Replacement: public: std::string StringWidgetValue(const std::string &_name) const
- Deprecation: public: math::Vector3 GetVector3WidgetValue(const std::string &_name)
- Replacement: public: ignition::math::Vector3d Vector3dWidgetValue(const std::string &_name) const
- Deprecation: public: common::Color GetColorWidgetValue(const std::string &_name) const
- Replacement: public: common::Color ColorWidgetValue(const std::string &_name) const
- Deprecation: public: math::Pose GetPoseWidgetValue(const std::string &_name) const
- Replacement: public: ignition::math::Pose3d PoseWidgetValue(const std::string &_name) const
- Deprecation: public: std::string GetGeometryWidgetValue(const std::string &_name, math::Vector3 &_dimensions, std::string &_uri) const
- Replacement: public: std::string GeometryWidgetValue(const std::string &_name, ignition::math::Vector3d &_dimensions, std::string &_uri) const
- Deprecation: public: std::string GetEnumWidgetValue(const std::string &_name) const
- Replacement: public: std::string EnumWidgetValue(const std::string &_name) const
-
gazebo/gui/GLWidget.hh
- Deprecation: rendering::UserCameraPtr GetCamera() const
- Replacement: rendering::UserCameraPtr Camera() const
- Deprecation: rendering::ScenePtr GetScene() const
- Replacement: rendering::ScenePtr Scene() const
-
gazebo/gui/KeyEventHandler.hh
- Deprecation: bool GetAutoRepeat() const
- Replacement: bool AutoRepeat() const
-
gazebo/gui/MainWindow.hh
- Deprecation: gui::RenderWidget *GetRenderWidget() const
- Replacement: gui::RenderWidget *RenderWidget() const
- Deprecation: gui::Editor *GetEditor(const std::string &_name) const
- Replacement: gui::Editor *Editor(const std::string &_name) const
-
gazebo/rendering/Camera.hh
- Deprecation: public: DistortionPtr GetDistortion() const;
- Replacement: public: DistortionPtr LensDistortion() const;
- Deprecation: public: double GetRenderRate() const;
- Replacement: public: double RenderRate() const;
- Deprecation: public: bool GetInitialized() const;
- Replacement: public: bool Initialized() const;
- Deprecation: public: unsigned int GetWindowId() const;
- Replacement: public: unsigned int WindowId() const;
- Deprecation: public: math::Vector3 GetWorldPosition() const
- Replacement: public: ignition::math::Vector3d WorldPosition() const;
- Deprecation: public: math::Quaternion GetWorldRotation() const
- Replacement: public: ignition::math::Quaterniond WorldRotation() const;
- Deprecation: public: virtual void SetWorldPose(const math::Pose &_pose)
- Replacement: public: virtual void SetWorldPose(const ignition::math::Pose3d &_pose);
- Deprecation: public: math::Pose GetWorldPose() const
- Replacement: public: ignition::math::Pose3d WorldPose() const;
- Deprecation: public: void SetWorldPosition(const math::Vector3 &_pos);
- Replacement: public: void SetWorldPosition(const ignition::math::Vector3d &_pos);
- Deprecation: public: void SetWorldRotation(const math::Quaternion &_quat);
- Replacement: public: void SetWorldRotation(const ignition::math::Quaterniond &_quat);
- Deprecation: public: void Translate(const math::Vector3 &_direction)
- Replacement: public: void Translate(const ignition::math::Vector3d &_direction);
- Deprecation: public: void Roll(const math::Angle &_angle, Ogre::Node::TransformSpace _relativeTo =Ogre::Node::TS_LOCAL);
- Replacement: public: void Roll(const ignition::math::Angle &_angle, ReferenceFrame _relativeTo = RF_LOCAL);
- Deprecation: public: void Pitch(const math::Angle &_angle, Ogre::Node::TransformSpace _relativeTo =Ogre::Node::TS_LOCAL);
- Replacement: public: void Pitch(const ignition::math::Angle &_angle, ReferenceFrame _relativeTo = RF_LOCAL);
- Deprecation: public: void Yaw(const math::Angle &_angle, Ogre::Node::TransformSpace _relativeTo =Ogre::Node::TS_WORLD);
- Replacement: public: void Yaw(const ignition::math::Angle &_angle, ReferenceFrame _relativeTo = RF_WORLD);
- Deprecation: public: void SetHFOV(math::Angle _angle);
- Replacement: public: void SetHFOV(const ignition::math::Angle &_angle);
- Deprecation: public: math::Angle GetHFOV() const
- Replacement: public: ignition::math::Angle HFOV() const;
- Deprecation: public: math::Angle GetVFOV() const;
- Replacement: public: ignition::math::Angle VFOV() const;
- Deprecation: public: virtual unsigned int GetImageWidth() const;
- Replacement: public: virtual unsigned int ImageWidth() const;
- Deprecation: public: unsigned int GetTextureWidth() const;
- Replacement: public: unsigned int TextureWidth() const;
- Deprecation: public: virtual unsigned int GetImageHeight() const;
- Replacement: public: virtual unsigned int ImageHeight() const;
- Deprecation: public: unsigned int GetImageDepth() const;
- Replacement: public: unsigned int ImageDepth() const;
- Deprecation: public: std::string GetImageFormat() const;
- Replacement: public: std::string ImageFormat() const;
- Deprecation: public: unsigned int GetTextureHeight() const;
- Replacement: public: unsigned int TextureHeight() const;
- Deprecation: public: size_t GetImageByteSize() const;
- Replacement: public: size_t ImageByteSize() const;
- Deprecation: public: static size_t GetImageByteSize(unsigned int _width, unsigned int _height, const std::string &_format);
- Replacement: static size_t ImageByteSize(const unsigned int _width, const unsigned int _height, const std::string &_format);
- Deprecation: public: double GetZValue(int _x, int _y);
- Replacement: public: double ZValue(const int _x, const int _y);
- Deprecation: public: double GetNearClip();
- Replacement: public: double NearClip() const;
- Deprecation: public: double GetFarClip();
- Replacement: public: double FarClip() const;
- Deprecation: public: bool GetCaptureData() const;
- Replacement: public: bool CaptureData() const;
- Deprecation: public: Ogre::Camera *GetOgreCamera() const;
- Replacement: public: Ogre::Camera *OgreCamera() const;
- Deprecation: public: Ogre::Viewport *GetViewport() const;
- Replacement: public: Ogre::Viewport *OgreViewport() const;
- Deprecation: public: unsigned int GetViewportWidth() const;
- Replacement: public: unsigned int ViewportWidth() const;
- Deprecation: public: unsigned int GetViewportHeight() const;
- Replacement: public: unsigned int ViewportHeight() const;
- Deprecation: public: math::Vector3 GetUp();
- Replacement: public: ignition::math::Vector3d Up() const;
- Deprecation: public: math::Vector3 GetRight();
- Replacement: public: ignition::math::Vector3d Right() const;
- Deprecation: public: virtual float GetAvgFPS() const;
- Replacement: public: virtual float AvgFPS() const;
- Deprecation: public: virtual unsigned int GetTriangleCount() const;
- Replacement: public: virtual unsigned int TriangleCount() const;
- Deprecation: public: float GetAspectRatio() const;
- Replacement: public: float AspectRatio() const;
- Deprecation: public: Ogre::SceneNode *GetSceneNode() const;
- Replacement: public: Ogre::SceneNode *SceneNode() const;
- Deprecation: public: virtual const unsigned char *GetImageData(unsigned int i = 0);
- Replacement: public: virtual const unsigned char *ImageData(unsigned int i = 0) const;
- Deprecation: public: std::string GetName() const;
- Replacement: public: std::string Name() const;
- Deprecation: public: std::string GetScopedName() const;
- Replacement: public: std::string ScopedName() const;
- Deprecation: public: void GetCameraToViewportRay(int _screenx, int _screeny,math::Vector3 &_origin, math::Vector3 &_dir);
- Replacement: public: void CameraToViewportRay(const int _screenx, const int _screeny,ignition::math::Vector3d &_origin,ignition::math::Vector3d &_dir) const;
- Deprecation: public: bool GetWorldPointOnPlane(int _x, int _y,const math::Plane &_plane, math::Vector3 &_result);
- Replacement: public: bool WorldPointOnPlane(const int _x, const int _y, const ignition::math::Planed &_plane,ignition::math::Vector3d &_result);
- Deprecation: public: Ogre::Texture *GetRenderTexture() const;
- Replacement: public: Ogre::Texture *RenderTexture() const;
- Deprecation: public: math::Vector3 GetDirection();
- Replacement: public: ignition::math::Vector3d Direction() const;
- Deprecation: public: common::Time GetLastRenderWallTime();
- Replacement: public: common::Time LastRenderWallTime() const;
- Deprecation: public: virtual bool MoveToPosition(const math::Pose &_pose,double _time);
- Replacement: public: virtual bool MoveToPosition(const ignition::math::Pose3d &_pose,double _time);
- Deprecation: public: bool MoveToPositions(const std::vectormath::Pose &_pts,double _time,boost::function<void()> _onComplete = NULL);
- Replacement: public: bool MoveToPositions(const std::vectorignition::math::Pose3d &_pts,double _time,boost::function<void()> _onComplete = NULL);
- Deprecation: public: std::string GetScreenshotPath() const;
- Replacement: public: std::string ScreenshotPath() const;
- Deprecation: public: std::string GetProjectionType() const;
- Replacement: public: std::string ProjectionType() const;
-
gazebo/gui/RTShaderSystem.hh
- Deprecation: void AttachEntity(Visual *vis)
- ***No replacement for AttachEntity ***
-
gazebo/gui/RTShaderSystem.hh
- Deprecation: void DetachEntity(Visual *_vis)
- ***No replacement for DetachEntity ***
-
gazebo/physics/Model.hh
- Deprecation: public: void SetScale(const math::Vector3 &_scale);
- Replacement: public: void SetScale(const ignition::math::Vector3d &_scale, const bool _publish = false);
-
plugins/rest_web/RestUiLogoutDialog.hh.hh
-
gazebo rendering libraries
- The following libraries have been removed:
libgazebo_skyx
,libgazebo_selection_buffer
,libgazebo_rendering_deferred
. Gazebo now combines all the different rendering libraries intolibgazebo_rendering.so
. - Pull request #1817
- The following libraries have been removed:
-
gazebo physics libraries
- The following libraries have been removed:
libgazebo_ode_physics
,libgazebo_simbody_physics
,libgazebo_dart_physics
, andlibgazebo_bullet_physics
. Gazebo now combines all the different physics engine libraries intolibgazebo_physics.so
. - Pull request #1814
- The following libraries have been removed:
-
gazebo/gui/BoxMaker.hh
-
gazebo/gui/CylinderMaker.hh
-
gazebo/gui/SphereMaker.hh
-
gazebo/gui/MeshMaker.hh
-
gazebo/gui/EntityMaker.hh
- public: typedef boost::function<void(const math::Vector3 &pos, const math::Vector3 &scale)> CreateCallback;
- public: static void SetSnapToGrid(bool _snap);
- public: virtual bool IsActive() const = 0;
- public: virtual void OnMousePush(const common::MouseEvent &_event);
- public: virtual void OnMouseDrag(const common::MouseEvent &_event);
- protected: math::Vector3 GetSnappedPoint(math::Vector3 _p);
-
gazebo/sensors/ForceTorqueSensor.hh
- public: math::Vector3 GetTorque() const
- public: math::Vector3 GetForce() const
-
gazebo/sensors/GpsSensor.hh
- public: math::Angle GetLongitude()
- public: math::Angle GetLatitude()
-
gazebo/sensors/GpuRaySensor.hh
- public: math::Angle GetAngleMin() const
- public: math::Angle GetAngleMax() const
- public: math::Angle GetVerticalAngleMin() const
- public: math::Angle GetVerticalAngleMax() const
-
gazebo/sensors/ImuSensor.hh
- public: math::Vector3 GetAngularVelocity() const
- public: math::Vector3 GetLinearAcceleration() const
- public: math::Quaternion GetOrientation() const
-
gazebo/sensors/RFIDSensor.hh
- private: bool CheckTagRange(const math::Pose &_pose)
-
gazebo/sensors/RFIDTag.hh
- public: math::Pose GetTagPose() const
-
gazebo/sensors/RaySensor.hh
- public: math::Angle GetAngleMin() const
- public: math::Angle GetAngleMax() const
- public: math::Angle GetVerticalAngleMin() const
- public: math::Angle GetVerticalAngleMax() const
-
gazebo/sensors/Sensor.hh
- public: virtual math::Pose GetPose() const
- public: NoisePtr GetNoise(unsigned int _index = 0) const
-
gazebo/sensors/WirelessTransmitter.hh
- public: double GetSignalStrength(const math::Pose &_receiver, const double _rxGain)
-
gazebo/common/Color.hh
- Deprecation: math::Vector3 GetAsHSV() const;
- Replacement: ignition::math::Vector3d HSV() const;
-
gazebo/common/Dem.hh
- Deprecation: void GetGeoReferenceOrigin(math::Angle &_latitude,math::Angle &_longitude);
- Replacement: void GetGeoReferenceOrigin(ignition::math::Angle &_latitude, ignition::math::Angle &_longitude) const;
- ***Deprecation:***void FillHeightMap(int _subSampling, unsigned int _vertSize, const math::Vector3 &_size, const math::Vector3 &_scale, bool _flipY, std::vector &_heights);
- ***Replacement:***void FillHeightMap(const int _subSampling, const unsigned int _vertSize, const ignition::math::Vector3d &_size, const ignition::math::Vector3d &_scale, const bool _flipY, std::vector &_heights);
-
gazebo/common/GTSMeshUtils.hh
- ***Deprecation:***static bool DelaunayTriangulation(const std::vectormath::Vector2d &_vertices, const std::vectormath::Vector2i &_edges, SubMesh *_submesh);
- ***Replacement:***static bool DelaunayTriangulation( const std::vectorignition::math::Vector2d &_vertices, const std::vectorignition::math::Vector2i &_edges, SubMesh *_submesh);
-
gazebo/common/HeightmapData.hh
- ***Deprecation:***virtual void FillHeightMap(int _subSampling,unsigned int _vertSize, const math::Vector3 &_size,const math::Vector3 &_scale, bool _flipY, std::vector &_heights);
- ***Replacement:***void FillHeightMap(int _subSampling,unsigned int _vertSize, const ignition::math::Vector3d &_size,const ignition::math::Vector3d &_scale, bool _flipY,std::vector &_heights);
-
gazebo/common/KeyFrame.hh
- ***Deprecation:***void SetTranslation(const math::Vector3 &_trans);
- ***Replacement:***void Translation(const ignition::math::Vector3d &_trans);
- ***Deprecation:***math::Vector3 GetTranslation() const;
- ***Replacement:***ignition::math::Vector3d Translation() const;
- ***Deprecation:***void SetRotation(const math::Quaternion &_rot);
- ***Replacement:***void Rotation(const ignition::math::Quaterniond &_rot);
- ***Deprecation:***math::Quaternion GetRotation();
- ***Replacement:***ignition::math::Quaterniond Rotation() const;
-
gazebo/common/Mesh.hh
- ***Deprecation:***math::Vector3 GetMax() const;
- ***Replacement:***ignition::math::Vector3d Max() const;
- ***Deprecation:***math::Vector3 GetMin() const;
- ***Replacement:***ignition::math::Vector3d Min() const;
- ***Deprecation:***void GetAABB(math::Vector3 &_center, math::Vector3 &_min_xyz,math::Vector3 &_max_xyz) const;
- ***Replacement:***void GetAABB(ignition::math::Vector3d &_center,ignition::math::Vector3d &_minXYZ,ignition::math::Vector3d &_maxXYZ) const;
- ***Deprecation:***void GenSphericalTexCoord(const math::Vector3 &_center);
- ***Replacement:***void GenSphericalTexCoord(const ignition::math::Vector3d &_center);
- ***Deprecation:***void SetScale(const math::Vector3 &_factor);
- ***Replacement:***void SetScale(const ignition::math::Vector3d &_factor);
- ***Deprecation:***void Center(const math::Vector3 &_center = math::Vector3::Zero);
- ***Replacement:***void Center(const ignition::math::Vector3d &_center =ignition::math::Vector3d::Zero);
- ***Deprecation:***void Translate(const math::Vector3 &_vec);
- ***Replacement:***void Translate(const ignition::math::Vector3d &_vec);
- Deprecation: void CopyVertices(const std::vectormath::Vector3 &_verts);
- ***Replacement:***void CopyVertices(const std::vectorignition::math::Vector3d &_verts);
- ***Deprecation:***void CopyNormals(const std::vectormath::Vector3 &_norms);
- ***Replacement:***void CopyNormals( const std::vectorignition::math::Vector3d &_norms);
- ***Deprecation:***void AddVertex(const math::Vector3 &_v);
- ***Replacement:***void AddVertex(const ignition::math::Vector3d &_v);
- ***Deprecation:***void AddNormal(const math::Vector3 &_n);
- ***Replacement:***void AddNormal(const ignition::math::Vector3d &_n);
- ***Deprecation:***math::Vector3 GetVertex(unsigned int _i) const;
- ***Replacement:***ignition::math::Vector3d Vertex(unsigned int _i) const;
- ***Deprecation:***void SetVertex(unsigned int _i, const math::Vector3 &_v);
- ***Replacement:***void SetVertex(unsigned int _i,const ignition::math::Vector3d &_v);
- ***Deprecation:***math::Vector3 GetNormal(unsigned int _i) const;
- ***Replacement:***ignition::math::Vector3d Normal(unsigned int _i) const;
- ***Deprecation:***void SetNormal(unsigned int _i, const math::Vector3 &_n);
- ***Replacement:***void SetNormal(unsigned int _i,const ignition::math::Vector3d &_n);
- ***Deprecation:***math::Vector2d GetTexCoord(unsigned int _i) const;
- ***Replacement:***ignition::math::Vector2d TexCoord(unsigned int _i) const;
- ***Deprecation:***void SetTexCoord(unsigned int _i, const math::Vector2d &_t);
- ***Replacement:***void SetTexCoord(unsigned int _i,const ignition::math::Vector2d &_t);
- ***Deprecation:***math::Vector3 GetMax() const;
- ***Replacement:***ignition::math::Vector3d Max() const;
- ***Deprecation:***math::Vector3 GetMin() const;
- ***Replacement:***ignition::math::Vector3d Min() const;
- ***Deprecation:***bool HasVertex(const math::Vector3 &_v) const;
- ***Replacement:***bool HasVertex(const ignition::math::Vector3d &_v) const;
- ***Deprecation:***unsigned int GetVertexIndex(const math::Vector3 &_v) const;
- ***Replacement:***unsigned int GetVertexIndex( const ignition::math::Vector3d &_v) const;
- ***Deprecation:***void GenSphericalTexCoord(const math::Vector3 &_center);
- ***Replacement:***void GenSphericalTexCoord(const ignition::math::Vector3d &_center);
- ***Deprecation:***void Center(const math::Vector3 &_center = math::Vector3::Zero);
- ***Replacement:***void Center(const ignition::math::Vector3d &_center =ignition::math::Vector3d::Zero);
- ***Deprecation:***void Translate(const math::Vector3 &_vec) ;
- ***Replacement:***void Translate(const ignition::math::Vector3d &_vec);
- ***Deprecation:***void SetScale(const math::Vector3 &_factor);
- ***Replacement:***void SetScale(const ignition::math::Vector3d &_factor);
-
gazebo/common/MeshCSG.hh
- ***Deprecation:***Mesh *CreateBoolean(const Mesh *_m1, const Mesh *_m2,const int _operation, const math::Pose &_offset = math::Pose::Zero);
- ***Replacement:***Mesh *CreateBoolean(const Mesh *_m1, const Mesh *_m2,const int _operation,const ignition::math::Pose3d &_offset = ignition::math::Pose3d::Zero);
-
gazebo/common/MeshManager.hh
- ***Deprecation:***void GetMeshAABB(const Mesh *_mesh,math::Vector3 &_center,math::Vector3 &_minXYZ,math::Vector3 &_maxXYZ);
- ***Replacement:***void GetMeshAABB(const Mesh *_mesh,ignition::math::Vector3d &_center,ignition::math::Vector3d &_min_xyz,ignition::math::Vector3d &_max_xyz);
- ***Deprecation:***void GenSphericalTexCoord(const Mesh *_mesh,math::Vector3 _center);
- Replacement: void GenSphericalTexCoord(const Mesh *_mesh,const ignition::math::Vector3d &_center);
- ***Deprecation:***void CreateBox(const std::string &_name, const math::Vector3 &_sides,const math::Vector2d &_uvCoords);
- ***Replacement:***void CreateBox(const std::string &_name,const ignition::math::Vector3d &_sides,const ignition::math::Vector2d &_uvCoords);
- ***Deprecation:***void CreateExtrudedPolyline(const std::string &_name, const std::vector<std::vectormath::Vector2d > &_vertices,double _height);
- Replacement: void CreateExtrudedPolyline(const std::string &_name,const std::vector<std::vectorignition::math::Vector2d > &_vertices, double _height);
- ***Deprecation:***void CreatePlane(const std::string &_name,const math::Plane &_plane,const math::Vector2d &_segments,const math::Vector2d &_uvTile);
- ***Replacement:***void CreatePlane(const std::string &_name,const ignition::math::Planed &_plane,const ignition::math::Vector2d &_segments, const ignition::math::Vector2d &_uvTile);
- ***Deprecation:***void CreatePlane(const std::string &_name,const math::Vector3 &_normal,double _d,const math::Vector2d &_size,const math::Vector2d &_segments,const math::Vector2d &_uvTile);
- ***Replacement:***void CreatePlane(const std::string &_name,const ignition::math::Vector3d &_normal,const double _d,const ignition::math::Vector2d &_size,const ignition::math::Vector2d &_segments, const ignition::math::Vector2d &_uvTile);
- ***Deprecation:***void CreateBoolean(const std::string &_name, const Mesh *_m1,const Mesh *_m2, const int _operation,const math::Pose &_offset = math::Pose::Zero);
- ***Replacement:***void CreateBoolean(const std::string &_name, const Mesh *_m1,const Mesh *_m2, const int _operation,const ignition::math::Pose3d &_offset = ignition::math::Pose3d::Zero);
-
gazebo/common/SVGLoader.hh
- ***Deprecation:***static void PathsToClosedPolylines(const std::vectorcommon::SVGPath &_paths, double _tol,std::vector< std::vectormath::Vector2d > &_closedPolys,std::vector< std::vectormath::Vector2d > &_openPolys);
- ***Replacement:***static void PathsToClosedPolylines(const std::vectorcommon::SVGPath &_paths,double _tol,std::vector< std::vectorignition::math::Vector2d > &_closedPolys,std::vector< std::vectorignition::math::Vector2d > &_openPolys);
-
gazebo/common/Skeleton.hh
- ***Deprecation:***void SetBindShapeTransform(math::Matrix4 _trans);
- ***Replacement:***void SetBindShapeTransform(const ignition::math::Matrix4d &_trans);
- ***Deprecation:***math::Matrix4 GetBindShapeTransform();
- ***Replacement:***ignition::math::Matrix4d BindShapeTransform();
- ***Deprecation:***void SetTransform(math::Matrix4 _trans,bool _updateChildren = true);
- ***Replacement:***void SetTransform(const ignition::math::Matrix4d &_trans,bool _updateChildren = true);
- ***Deprecation:***void SetModelTransform(math::Matrix4 _trans,bool _updateChildren = true);
- ***Replacement:***void SetModelTransform(const ignition::math::Matrix4d &_trans,bool _updateChildren = true);
- ***Deprecation:***void SetInitialTransform(math::Matrix4 _tras);
- ***Replacement:***void SetInitialTransform(const ignition::math::Matrix4d &_tras);
- ***Deprecation:***math::Matrix4 GetTransform();
- ***Replacement:***ignition::math::Matrix4d Transform();
- ***Deprecation:***void SetInverseBindTransform(math::Matrix4 _invBM);
- ***Replacement:***void SetInverseBindTransform(const ignition::math::Matrix4d &_invBM);
- ***Deprecation:***math::Matrix4 GetInverseBindTransform();
- ***Replacement:***ignition::math::Matrix4d InverseBindTransform();
- ***Deprecation:***math::Matrix4 GetModelTransform();
- ***Replacement:***ignition::math::Matrix4d ModelTransform() const;
- ***Deprecation:***NodeTransform(math::Matrix4 _mat, std::string _sid = "default",TransformType _type = MATRIX);
- ***Replacement:***NodeTransform(const ignition::math::Matrix4d &_mat,const std::string &_sid = "default",TransformType _type = MATRIX);
- ***Deprecation:***void Set(math::Matrix4 _mat);
- ***Replacement:***void Set(const ignition::math::Matrix4d &_mat);
- ***Deprecation:***math::Matrix4 Get();
- ***Replacement:***ignition::math::Matrix4d GetTransform() const;
- ***Deprecation:***void SetSourceValues(math::Matrix4 _mat);
- ***Replacement:***void SetSourceValues(const ignition::math::Matrix4d &_mat);
- ***Deprecation:***void SetSourceValues(math::Vector3 _vec);
- Replacement: void SetSourceValues(const ignition::math::Vector3d &_vec);
- ***Deprecation:***void SetSourceValues(math::Vector3 _axis, double _angle);
- ***Replacement:***void SetSourceValues(const ignition::math::Vector3d &_axis,const double _angle);
- ***Deprecation:**math::Matrix4 operator (math::Matrix4 _m);
- ***Replacement:**ignition::math::Matrix4d operator(const ignition::math::Matrix4d &_m);
-
gazebo/common/SkeletonAnimation.hh
- ***Deprecation:***void AddKeyFrame(const double _time, const math::Matrix4 &_trans);
- ***Replacement:***void AddKeyFrame(const double _time,const ignition::math::Matrix4d &_trans);
- ***Deprecation:***void AddKeyFrame(const double _time,const math::Pose &_pose);
- ***Replacement:***void AddKeyFrame(const double _time,const ignition::math::Pose3d &_pose);
- ***Deprecation:***void GetKeyFrame(const unsigned int _i, double &_time,math::Matrix4 &_trans);
- ***Replacement:***void GetKeyFrame(const unsigned int _i, double &_time,ignition::math::Matrix4d &_trans) const;
- ***Deprecation:***std::pair<double, math::Matrix4> GetKeyFrame(const unsigned int _i);
- ***Replacement:***std::pair<double, ignition::math::Matrix4d> KeyFrame(const unsigned int _i) const;
- ***Deprecation:***math::Matrix4 GetFrameAt(double _time, bool _loop = true) const;
- ***Replacement:***ignition::math::Matrix4d FrameAt(double _time, bool _loop = true) const;
- ***Deprecation:***void AddKeyFrame(const std::string &_node, const double _time, const math::Matrix4 &_mat);
- ***Replacement:***void AddKeyFrame(const std::string &_node, const double _time,const ignition::math::Matrix4d &_mat);
- ***Deprecation:***void AddKeyFrame(const std::string &_node, const double _time,const math::Pose &_pose);
- ***Replacement:***void AddKeyFrame(const std::string &_node, const double _time,const ignition::math::Pose3d &_pose);
- Deprecation: math::Matrix4 GetNodePoseAt(const std::string &_node,const double _time, const bool _loop = true);
- ***Replacement:***ignition::math::Matrix4d NodePoseAt(const std::string &_node,const double _time, const bool _loop = true);
- ***Deprecation:***std::map<std::string, math::Matrix4> GetPoseAt(const double _time, const bool _loop = true) const;
- ***Replacement:***std::map<std::string, ignition::math::Matrix4d> PoseAt(const double _time, const bool _loop = true) const;
- ***Deprecation:***std::map<std::string, math::Matrix4> GetPoseAtX(const double _x, const std::string &_node, const bool _loop = true) const;
- ***Replacement:***std::map<std::string, ignition::math::Matrix4d> PoseAtX(const double _x, const std::string &_node, const bool _loop = true) const;
-
gazebo/common/SphericalCoordinates.hh
- ***Deprecation:***SphericalCoordinates(const SurfaceType _type,const math::Angle &_latitude,const math::Angle &_longitude,double _elevation,const math::Angle &_heading);
- ***Replacement:***SphericalCoordinates(const SurfaceType _type,const ignition::math::Angle &_latitude,const ignition::math::Angle &_longitude,double _elevation,const ignition::math::Angle &_heading);
- ***Deprecation:***math::Vector3 SphericalFromLocal(const math::Vector3 &_xyz) const;
- ***Replacement:***ignition::math::Vector3d SphericalFromLocal(const ignition::math::Vector3d &_xyz) const;
- ***Deprecation:***math::Vector3 GlobalFromLocal(const math::Vector3 &_xyz) const;
- ***Replacement:***ignition::math::Vector3d GlobalFromLocal(const ignition::math::Vector3d &_xyz) const;
- ***Deprecation:***static double Distance(const math::Angle &_latA,const math::Angle &_lonA,const math::Angle &_latB,const math::Angle &_lonB);
- ***Replacement:***static double Distance(const ignition::math::Angle &_latA,const ignition::math::Angle &_lonA,const ignition::math::Angle &_latB,const ignition::math::Angle &_lonB);
- Deprecation: math::Angle GetLatitudeReference() const;
- ***Replacement:***ignition::math::Angle LatitudeReference() const;
- ***Deprecation:***math::Angle GetLongitudeReference() const;
- ***Replacement:***ignition::math::Angle LongitudeReference() const;
- ***Deprecation:***math::Angle GetHeadingOffset() const;
- ***Replacement:***ignition::math::Angle HeadingOffset() const;
- ***Deprecation:***void SetLatitudeReference(const math::Angle &_angle);
- ***Replacement:***void SetLatitudeReference(const ignition::math::Angle &_angle);
- ***Deprecation:***void SetLongitudeReference(const math::Angle &_angle);
- ***Replacement:***void SetLongitudeReference(const ignition::math::Angle &_angle);
- ***Deprecation:***void SetHeadingOffset(const math::Angle &_angle);
- ***Replacement:***void SetHeadingOffset(const ignition::math::Angle &_angle);
-
gazebo/common/MouseEvent.hh
- Replaced all member variables with functions that use Ignition Math.
- Pull request #1777
-
gazebo/msgs/world_stats.proto
- Removed: optional bool log_playback = 8;
- Replacement: optional LogPlaybackStatistics log_playback_stats = 8;
-
gazebo/physics/JointState.hh
- Removed: public: JointState(JointPtr _joint, const common::Time &_realTime, const common::Time &_simTime)
- Replacement: public: JointState(JointPtr _joint, const common::Time &_realTime, const common::Time &_simTime, const uint64_t _iterations)
-
gazebo/physics/LinkState.hh
- Removed: public: LinkState(const LinkPtr _link, const common::Time &_realTime, const common::Time &_simTime)
- Replacement: public: LinkState(const LinkPtr _link, const common::Time &_realTime, const common::Time &_simTime, const uint64_t _iterations)
- Removed: public: void Load(const LinkPtr _link, const common::Time &_realTime, const common::Time &_simTime)
- Replacement: public: void Load(const LinkPtr _link, const common::Time &_realTime, const common::Time &_simTime, const uint64_t _iterations)
-
gazebo/physics/ModelState.hh
- Removed: public: ModelState(const ModelPtr _model, const common::Time &_realTime, const common::Time &_simTime)
- Replacement: public: ModelState(const ModelPtr _model, const common::Time &_realTime, const common::Time &_simTime, const uint64_t _iterations)
- Removed: public: void Load(const ModelPtr _model, const common::Time &_realTime, const common::Time &_simTime)
- Replacement: public: void Load(const ModelPtr _model, const common::Time &_realTime, const common::Time &_simTime, const uint64_t _iterations)
-
gazebo/physics/State.hh
- Removed: public: State(const std::string &_name, const common::Time &_realTime, const common::Time &_simTime)
- Replacement: public: State(const std::string &_name, const common::Time &_realTime, const common::Time &_simTime, const uint64_t _iterations)
-
gazebo/physics/ModelState.hh
- Removed: public: void Load(const ModelPtr _model, const common::Time &_realTime, const common::Time &_simTime)
- Replacement: public: void Load(const ModelPtr _model, const common::Time &_realTime, const common::Time &_simTime, const uint64_t _iterations)
-
ignition-math is now a dependency. Many classes and functions are modified to use ignition-math, please see the pull request listing below for individual changes.
-
Gazebo client's should now use
gazebo/gazebo_client.hh
andlibgazebo_client.so
instead ofgazebo/gazebo.hh
andlibgazebo.so
. This separates running a Gazebo server from a Gazebo client.- Removed: bool gazebo::setupClient(int _argc = 0, char **_argv = 0);
- Replacement: bool gazebo::client::setup(int _argc = 0, char **_argv = 0);
-
gazebo/rendering/GpuLaser.hh
- Removed: protected: double near
- Replacement: protected: double nearClip
-
gazebo/rendering/GpuLaser.hh
- Removed: protected: double far
- Replacement: protected: double farClip
-
gazebo/rendering/Visual.hh
- Removed: public: void Fini();
- Replacement: public: virtual void Fini();
-
gazebo/common/MeshManager.hh
- Removed: void CreateExtrudedPolyline(const std::string &_name, const std::vectormath::Vector2d &_vertices, const double &_height, const math::Vector2d &_uvCoords)
- Replacement: void CreateExtrudedPolyline(const std::string &_name, const const std::vector<std::vectormath::Vector2d > &_vertices, const double &_height, const math::Vector2d &_uvCoords)
-
gazebo/common/GTSMeshUtils.hh
- Removed: public: static bool CreateExtrudedPolyline(const std::vectormath::Vector2d &_vertices, const double &_height, SubMesh *_submesh)
- Replacement: public: static bool DelaunayTriangulation(const std::vector<std::vectormath::Vector2d > &_path, SubMesh *_submesh)
-
gazebo/physics/PolylineShape.hh
- Removed: public: std::vectormath::Vector2d GetVertices() const
- Replacement: public: std::vector<std::vectormath::Vector2d > GetVertices() const
-
gazebo/physics/SurfaceParams.hh
- Removed: public: FrictionPyramid frictionPyramid
- Replacement: public: FrictionPyramidPtr GetFrictionPyramid() const
- gazebo/gui/RenderWidget.hh
- The ShowEditor(bool _show)
-
gazebo/msgs/log_playback_control.proto
- New message to control the playback from a log file.
-
gazebo/util/LogPlay.hh
- public: bool Rewind()
-
gazebo/physics/LinkState.hh
- public: virtual void SetIterations(const uint64_t _iterations)
-
gazebo/physics/ModelState.hh
- public: virtual void SetIterations(const uint64_t _iterations)
-
gazebo/physics/State.hh
- public: uint64_t GetIterations() const
- public: virtual void SetIterations(const uint64_t _iterations)
-
gazebo/physics/WorldState.hh
- public: virtual void SetIterations(const uint64_t _iterations)
-
gazebo/util/LogPlay.hh
- public: uint64_t GetInitialIterations() const
- public: bool HasIterations() const
Gazebo 5.x uses features from the new c++11 standard. This requires to have a compatible c++11 compiler. Note that some platforms (like Ubuntu Precise) do not include one by default.
-
Privatized World::dirtyPoses
- World::dirtyPoses used to be a public attribute. This is now a private attribute, and specific "friends" have been added to the World file.
-
Privatized Scene::skyx
- Scene::skyx used to be a public attribute. This is now a private attribute, and a GetSkyX() funcion has been added to access the sky object.
-
gazebo/rendering/Visual.hh
- The GetBoundingBox() function now returns a local bounding box without scale applied.
-
gazebo/math/Box.hh
- The constructor that takes two math::Vector3 values now treats these as two corners, and computes the minimum and maximum values automatically. This change is API and ABI compatible.
-
Informational logs: The log files will be created inside ~/.gazebo/server-<GAZEBO_MASTER_PORT> and ~/.gazebo/client-<GAZEBO_MASTER_PORT>. The motivation for this change is to avoid name collisions when cloning a simulation. If the environment variable GAZEBO_MASTER_URI is not present or invalid, <GAZEBO_MASTER_PORT> will be replaced by "default".
-
gazebo/common/Plugin.hh
- Removed: protected: std::string Plugin::handle
- Replacement: protected: std::string Plugin::handleName
-
gazebo/gui/KeyEventHandler.hh
- Removed: public: void HandlePress(const common::KeyEvent &_event);
- Replacement: public: bool HandlePress(const common::KeyEvent &_event);
-
gazebo/gui/KeyEventHandler.hh
- Removed: public: void HandleRelease(const common::KeyEvent &_event);
- Replacement: public: bool HandleRelease(const common::KeyEvent &_event);
-
gazebo/rendering/UserCamera.hh
- Removed: private: void OnJoy(ConstJoystickPtr &_msg)
- Replacement: private: void OnJoyTwist(ConstJoystickPtr &_msg)
-
gazebo/rendering/Camera.hh
- Deprecation: public: void RotatePitch(math::Angle _angle);
- Replacement: public: void Pitch(const math::Angle &_angle, Ogre::Node::TransformSpace _relativeTo = Ogre::Node::TS_LOCAL);
- Deprecation: public: void RotateYaw(math::Angle _angle);
- Replacement: public: void Yaw(const math::Angle &_angle, Ogre::Node::TransformSpace _relativeTo = Ogre::Node::TS_LOCAL);
-
gazebo/rendering/AxisVisual.hh
- Removed: public: void ShowRotation(unsigned int _axis)
- Replacement: public: void ShowAxisRotation(unsigned int _axis, bool _show)
-
gazebo/rendering/ArrowVisual.hh
- Removed: public: void ShowRotation()
- Replacement: public: void ShowRotation(bool _show)
-
gazebo/physics/Collision.hh
- unsigned int GetShapeType()
-
gazebo/physics/World.hh
- EntityPtr GetSelectedEntity() const
-
gazebo/physics/bullet/BulletJoint.hh
- void SetAttribute(Attribute, unsigned int, double)
-
gazebo/physics/simbody/SimbodyJoint.hh
- void SetAttribute(Attribute, unsigned int, double)
-
gazebo/physics/Collision.hh
- Deprecation unsigned int GetShapeType()
- Replacement unsigned int GetShapeType() const
-
gazebo/physics/Joint.hh
- Deprecation virtual double GetMaxForce(unsigned int)
- Deprecation virtual void SetMaxForce(unsigned int, double)
- Deprecation virtual void SetAngle(unsigned int, math::Angle)
- Replacement virtual void SetPosition(unsigned int, double)
-
gazebo/physics/Model.hh
- Removed: Link_V GetLinks() const
ABI Change
- Replacement: const Link_V &GetLinks() const
- Removed: Link_V GetLinks() const
-
gzprop command line tool
- The
gzprop
command line tool outputs a zip file instead of a tarball.
- The
-
gazebo/msgs/msgs.hh
- sdf::ElementPtr LightToSDF(const msgs::Light &_msg, sdf::ElementPtr _sdf = sdf::ElementPtr())
-
gazebo/rendering/Light.hh
- math::Quaternion GetRotation() const
- void SetRotation(const math::Quaternion &_q)
- LightPtr Clone(const std::string &_name, ScenePtr _scene)
-
gazebo/rendering/Scene.hh
- void AddLight(LightPtr _light)
- void RemoveLight(LightPtr _light)
-
gazebo/gui/GuiEvents.hh
- template static event::ConnectionPtr ConnectLightUpdate(T _subscriber)
- static void DisconnectLightUpdate(event::ConnectionPtr _subscriber)
-
gazebo/gui/ModelMaker.hh
- bool InitFromModel(const std::string & _modelName)
-
gazebo/gui/LightMaker.hh
- bool InitFromLight(const std::string & _lightName)
-
gazebo/common/Mesh.hh
- int GetMaterialIndex(const Material *_mat) const
-
gazebo/math/Filter.hh
- New classes: Filter, OnePole, OnePoleQuaternion, OnePoleVector3, BiQuad, and BiQuadVector3
-
gazebo/physics/Joint.hh
- bool FindAllConnectedLinks(const LinkPtr &_originalParentLink, Link_V &_connectedLinks);
- math::Pose ComputeChildLinkPose( unsigned int _index, double _position);
-
gazebo/physics/Link.hh
- void Move(const math::Pose &_worldRefernceFrameSrc, const math::Pose &_worldRefernceFrameDst);
- bool FindAllConnectedLinksHelper( const LinkPtr &_originalParentLink, Link_V &_connectedLinks, bool _fistLink = false);
- bool ContainsLink(const Link_V &_vector, const LinkPtr &_value);
- msgs::Visual GetVisualMessage(const std::string &_name)
-
gazebo/physics/Model.hh
- Removed: Link_V GetLinks() const
ABI Change
- Replacement: const Link_V &GetLinks() const
- Removed: Link_V GetLinks() const
-
gazebo/physics/Base.cc
- Removed std::string GetScopedName() const
- Replaced std::string GetScopedName(bool _prependWorldName=false) const
-
gazebo/physics/World.hh
- void RemoveModel(const std::string &_name);
- void RemoveModel(ModelPtr _model);
-
gazebo/physics/JointController.hh
- void SetPositionPID(const std::string &_jointName, const common::PID &_pid);
- void SetVelocityPID(const std::string &_jointName, const common::PID &_pid);
-
gazebo/physics/Joint.hh
- Deprecation virtual void ApplyDamping()
- Replacement virtual void ApplyStiffnessDamping()
- Deprecation double GetDampingCoefficient() const
- Replacement double GetDamping(int _index)
-
gazebo/physics/ode/ODEJoint.hh
- Deprecation void CFMDamping()
- Replacement void ApplyImplicitStiffnessDamping()
-
gazebo/physics/ScrewJoint.hh
- Deprecation virtual void SetThreadPitch(unsigned int _index, double _threadPitch) = 0
- Replacement virtual void SetThreadPitch(double _threadPitch) = 0
- Deprecation virtual void GetThreadPitch(unsigned int _index) = 0
- Replacement virtual void GetThreadPitch() = 0
-
gazebo/physics/bullet/BulletScrewJoint.hh
- Deprecation protected: virtual void Load(sdf::ElementPtr _sdf)
- Replacement public: virtual void Load(sdf::ElementPtr _sdf)
-
gazebo/physics/PhysicsEngine.hh
- Deprecation virtual void SetSORPGSPreconIters(unsigned int _iters)
- Replacement virtual bool SetParam(const std::string &_key, const boost::any &_value)
- Deprecation virtual void SetSORPGSIters(unsigned int _iters)
- Replacement virtual bool SetParam(const std::string &_key, const boost::any &_value)
- Deprecation virtual void SetSORPGSW(double _w)
- Replacement virtual bool SetParam(const std::string &_key, const boost::any &_value)
- Deprecation virtual int GetSORPGSPreconIters()
- Replacement virtual boost::any GetParam(const std::string &_key) const
- Deprecation virtual int GetSORPGSIters()
- Replacement virtual boost::any GetParam(const std::string &_key) const
- Deprecation virtual double GetSORPGSW()
- Replacement virtual boost::any GetParam(const std::string &_key) const
-
gazebo/physics/bullet/BulletPhysics.hh
- Deprecation virtual bool SetParam(BulletParam _param, const boost::any &_value)
- Replacement virtual bool SetParam(const std::string &_key, const boost::any &_value)
- Deprecation virtual boost::any GetParam(BulletParam _param) const
- Replacement virtual boost::any GetParam(const std::string &_key) const
-
gazebo/physics/ode/ODEPhysics.hh
- Deprecation virtual bool SetParam(ODEParam _param, const boost::any &_value)
- Replacement virtual bool SetParam(const std::string &_key, const boost::any &_value)
- Deprecation virtual boost::any GetParam(ODEParam _param) const
- Replacement virtual boost::any GetParam(const std::string &_key) const
-
gazebo/physics/dart/DARTPhysics.hh
- Deprecation virtual boost::any GetParam(DARTParam _param) const
- Replacement virtual boost::any GetParam(const std::string &_key) const
-
gazebo/physics/Joint.hh
- Deprecation virtual double GetAttribute(const std::string &_key, unsigned int _index) = 0
- Replacement virtual double GetParam(const std::string &_key, unsigned int _index) = 0;
-
gazebo/physics/bullet/BulletJoint.hh
- Deprecation virtual double GetAttribute(const std::string &_key, unsigned int _index)
- Replacement virtual double GetParam(const std::string &_key, unsigned int _index)
-
gazebo/physics/bullet/BulletScrewJoint.hh
- Deprecation virtual double GetAttribute(const std::string &_key, unsigned int _index)
- Replacement virtual double GetParam(const std::string &_key, unsigned int _index)
-
gazebo/physics/dart/DARTJoint.hh
- Deprecation virtual double GetParam(const std::string &_key, unsigned int _index)
- Replacement virtual double GetAttribute(const std::string &_key, unsigned int _index)
-
gazebo/physics/ode/ODEJoint.hh
- Deprecation virtual double GetParam(const std::string &_key, unsigned int _index)
- Replacement virtual double GetAttribute(const std::string &_key, unsigned int _index)
-
gazebo/physics/ode/ODEScrewJoint.hh
- Deprecation virtual double GetParam(const std::string &_key, unsigned int _index)
- Replacement virtual double GetAttribute(const std::string &_key, unsigned int _index)
-
gazebo/physics/ode/ODEUniversalJoint.hh
- Deprecation virtual double GetParam(const std::string &_key, unsigned int _index)
- Replacement virtual double GetAttribute(const std::string &_key, unsigned int _index)
-
gazebo/physics/simbody/SimbodyJoint.hh
- Deprecation virtual double GetParam(const std::string &_key, unsigned int _index)
- Replacement virtual double GetAttribute(const std::string &_key, unsigned int _index)
-
gazebo/physics/simbody/SimbodyScrewJoint.hh
- Deprecation virtual double GetParam(const std::string &_key, unsigned int _index)
- Replacement virtual double GetAttribute(const std::string &_key, unsigned int _index)
-
gazebo/physics/Joint.hh
- Deprecation virtual void SetAttribute(const std::string &_key, unsigned int _index, const boost::any &_value) = 0
- Replacement virtual bool SetParam(const std::string &_key, unsigned int _index, const boost::any &_value) = 0
-
gazebo/physics/bullet/BulletJoint.hh
- Deprecation virtual void SetAttribute(const std::string &_key, unsigned int _index, const boost::any &_value)
- Replacement virtual bool SetParam(const std::string &_key, unsigned int _index, const boost::any &_value)
-
gazebo/physics/dart/DARTJoint.hh
- Deprecation virtual void SetAttribute(const std::string &_key, unsigned int _index, const boost::any &_value)
- Replacement virtual bool SetParam(const std::string &_key, unsigned int _index, const boost::any &_value)
-
gazebo/physics/ode/ODEJoint.hh
- Deprecation virtual void SetAttribute(const std::string &_key, unsigned int _index, const boost::any &_value)
- Replacement virtual bool SetParam(const std::string &_key, unsigned int _index, const boost::any &_value)
-
gazebo/physics/ode/ODEScrewJoint.hh
- Deprecation virtual void SetAttribute(const std::string &_key, unsigned int _index, const boost::any &_value)
- Replacement virtual bool SetParam(const std::string &_key, unsigned int _index, const boost::any &_value)
-
gazebo/physics/ode/ODEUniversalJoint.hh
- Deprecation virtual void SetAttribute(const std::string &_key, unsigned int _index, const boost::any &_value)
- Replacement virtual bool SetParam(const std::string &_key, unsigned int _index, const boost::any &_value)
-
gazebo/physics/simbody/SimbodyJoint.hh
- Deprecation virtual void SetAttribute(const std::string &_key, unsigned int _index, const boost::any &_value)
- Replacement virtual bool SetParam(const std::string &_key, unsigned int _index, const boost::any &_value)
-
gazebo/physics/simbody/SimbodyScrewJoint.hh
- Deprecation virtual void SetAttribute(const std::string &_key, unsigned int _index, const boost::any &_value)
- Replacement virtual bool SetParam(const std::string &_key, unsigned int _index, const boost::any &_value)
-
gazebo/physics/Entity.hh
- Removed: inline const math::Pose &GetWorldPose() const
ABI change
- Replacement: inline virutal const math::Pose &GetWorldPose() const
- Removed: inline const math::Pose &GetWorldPose() const
-
gazebo/physics/Box.hh
- Removed: bool operator==(const Box &_b)
ABI Change
- Replacement: bool operator==(const Box &_b) const
- Removed: bool operator==(const Box &_b)
-
gazebo/gui/GuiIface.hh
- Removed: void load()
ABI change
- Replacement: bool load()
- Note: Changed return type from void to bool.
- Removed: void load()
-
Functions in joint classes use unsigned int, instead of int
- All functions in Joint classes (gazebo/physics/*Joint*) and subclasses (gazebo/physics/[ode,bullet,simbody,dart]/*Joint*) now use unsigned integers instead of integers when referring to a specific joint axis.
- Add const to Joint::GetInitialAnchorPose(), Joint::GetStopDissipation(), Joint::GetStopStiffness()
-
gazebo/sensors/Noise.hh
ABI change
- Removed: void Noise::Load(sdf::ElementPtr _sdf)
- Replacement: virtual void Noise::Load(sdf::ElementPtr _sdf)
- Removed: void Noise::~Noise()
- Replacement: virtual void Noise::~Noise()
- Removed: void Noise::Apply() const
- Replacement: void Noise::Apply()
- Note: Make Noise a base class and refactored out GaussianNoiseModel to its own class.
-
gazebo/transport/ConnectionManager.hh
- Removed: bool ConnectionManager::Init(const std::string &_masterHost, unsigned int _masterPort)
ABI change
- Replacement: bool ConnectionManager::Init(const std::string &_masterHost, unsigned int _masterPort, uint32_t _timeoutIterations = 30)
- Note: No changes to downstream code required. A third parameter has been added that specifies the number of timeout iterations. This parameter has a default value of 30.
- Removed: bool ConnectionManager::Init(const std::string &_masterHost, unsigned int _masterPort)
-
gazebo/transport/TransportIface.hh
- Removed: bool init(const std::string &_masterHost = "", unsigned int _masterPort = 0)
ABI change
- Replacement: bool init(const std::string &_masterHost = "", unsigned int _masterPort = 0, uint32_t _timeoutIterations = 30)
- Note: No changes to downstream code required. A third parameter has been added that specifies the number of timeout iterations. This parameter has a default value of 30.
- Removed: bool init(const std::string &_masterHost = "", unsigned int _masterPort = 0)
-
gazebo/transport/Publication.hh
- Removed: void Publish(MessagePtr _msg, boost::function<void(uint32_t)> _cb, uint32_t _id)
ABI change
- Replacement: int Publish(MessagePtr _msg, boost::function<void(uint32_t)> _cb, uint32_t _id)
- Note: Only the return type changed.
- Removed: void Publish(MessagePtr _msg, boost::function<void(uint32_t)> _cb, uint32_t _id)
-
gazebo/common/ModelDatabase.hh
API change
- Removed: void ModelDatabase::GetModels(boost::function<void (const std::map<std::string, std::string> &)> _func)
- Replacement: event::ConnectionPtr ModelDatabase::GetModels(boost::function<void (const std::map<std::string, std::string> &)> _func)
- Note: The replacement function requires that the returned connection shared pointer remain valid in order to receive the GetModels callback. Reset the shared pointer to stop receiving GetModels callback.
-
gazebo/physics/Collision.hh
API change
- Modified: SurfaceParamsPtr Collision::surface
- Note: Changed from
private
toprotected
-
gazebo/physics/MultiRayShape.hh
API change
- Removed: double MultiRayShape::GetRange(int _index)
- Replacement: double MultiRayShape::GetRange(unsigned int _index)
- Removed: double MultiRayShape::GetRetro(int _index)
- Replacement: double MultiRayShape::GetRetro(unsigned int _index)
- Removed: double MultiRayShape::GetFiducial(int _index)
- Replacement: double MultiRayShape::GetFiducial(unsigned int _index)
- Note: Changed argument type from int to unsigned int.
-
gazebo/physics/SurfaceParams.hh
- Removed: void FillMsg(msgs::Surface &_msg)
- Replacement: virtual void FillMsg(msgs::Surface &_msg)
-
gazebo/sensors/RaySensor.hh
API change
- Removed: double RaySensor::GetRange(int _index)
- Replacement: double RaySensor::GetRange(unsigned int _index)
- Removed: double RaySensor::GetRetro(int _index)
- Replacement: double RaySensor::GetRetro(unsigned int _index)
- Removed: double RaySensor::GetFiducial(int _index)
- Replacement: double RaySensor::GetFiducial(unsigned int _index)
- Note: Changed argument type from int to unsigned int.
-
gazebo/physics/PhysicsEngine.hh
- Removed virtual void SetParam(const std::string &_key, const boost::any &_value)
- Replacement virtual bool SetParam(const std::string &_key, const boost::any &_value)
-
gazebo/physics/ode/ODEPhysics.hh
- Removed virtual void SetParam(const std::string &_key, const boost::any &_value)
- Replacement virtual bool SetParam(const std::string &_key, const boost::any &_value)
-
gazebo/physics/bullet/BulletPhysics.hh
- Removed virtual void SetParam(const std::string &_key, const boost::any &_value)
- Replacement virtual bool SetParam(const std::string &_key, const boost::any &_value)
-
gazebo/physics/BallJoint.hh
- Removed virtual void SetHighStop(unsigned int /_index/, const math::Angle &/_angle/)
- Replacement virtual bool SetHighStop(unsigned int /_index/, const math::Angle &/_angle/)
- Removed virtual void SetLowStop(unsigned int /_index/, const math::Angle &/_angle/)
- Replacement virtual bool SetLowStop(unsigned int /_index/, const math::Angle &/_angle/)
-
gazebo/physics/Joint.hh
- Removed virtual void SetHighStop(unsigned int _index, const math::Angle &_angle)
- Replacement virtual bool SetHighStop(unsigned int _index, const math::Angle &_angle)
- Removed virtual void SetLowStop(unsigned int _index, const math::Angle &_angle)
- Replacement virtual bool SetLowStop(unsigned int _index, const math::Angle &_angle)
-
gazebo/physics/bullet/BulletBallJoint.hh
- Removed virtual void SetHighStop(unsigned int _index, const math::Angle &_angle)
- Replacement virtual bool SetHighStop(unsigned int _index, const math::Angle &_angle)
- Removed virtual void SetLowStop(unsigned int _index, const math::Angle &_angle)
- Replacement virtual bool SetLowStop(unsigned int _index, const math::Angle &_angle)
-
gazebo/physics/bullet/BulletHinge2Joint.hh
- Removed virtual void SetHighStop(unsigned int _index, const math::Angle &_angle)
- Replacement virtual bool SetHighStop(unsigned int _index, const math::Angle &_angle)
- Removed virtual void SetLowStop(unsigned int _index, const math::Angle &_angle)
- Replacement virtual bool SetLowStop(unsigned int _index, const math::Angle &_angle)
-
gazebo/physics/bullet/BulletHingeJoint.hh
- Removed virtual void SetHighStop(unsigned int _index, const math::Angle &_angle)
- Replacement virtual bool SetHighStop(unsigned int _index, const math::Angle &_angle)
- Removed virtual void SetLowStop(unsigned int _index, const math::Angle &_angle)
- Replacement virtual bool SetLowStop(unsigned int _index, const math::Angle &_angle)
-
gazebo/physics/bullet/BulletScrewJoint.hh
- Removed virtual void SetHighStop(unsigned int _index, const math::Angle &_angle)
- Replacement virtual bool SetHighStop(unsigned int _index, const math::Angle &_angle)
- Removed virtual void SetLowStop(unsigned int _index, const math::Angle &_angle)
- Replacement virtual bool SetLowStop(unsigned int _index, const math::Angle &_angle)
-
gazebo/physics/bullet/BulletSliderJoint.hh
- Removed virtual void SetHighStop(unsigned int _index, const math::Angle &_angle)
- Replacement virtual bool SetHighStop(unsigned int _index, const math::Angle &_angle)
- Removed virtual void SetLowStop(unsigned int _index, const math::Angle &_angle)
- Replacement virtual bool SetLowStop(unsigned int _index, const math::Angle &_angle)
-
gazebo/physics/bullet/BulletUniversalJoint.hh
- Removed virtual void SetHighStop(unsigned int _index, const math::Angle &_angle)
- Replacement virtual bool SetHighStop(unsigned int _index, const math::Angle &_angle)
- Removed virtual void SetLowStop(unsigned int _index, const math::Angle &_angle)
- Replacement virtual bool SetLowStop(unsigned int _index, const math::Angle &_angle)
-
gazebo/physics/dart/DARTJoint.hh
- Removed virtual void SetHighStop(unsigned int _index, const math::Angle &_angle)
- Replacement virtual bool SetHighStop(unsigned int _index, const math::Angle &_angle)
- Removed virtual void SetLowStop(unsigned int _index, const math::Angle &_angle)
- Replacement virtual bool SetLowStop(unsigned int _index, const math::Angle &_angle)
-
gazebo/physics/ode/ODEJoint.hh
- Removed virtual void SetHighStop(unsigned int _index, const math::Angle &_angle)
- Replacement virtual bool SetHighStop(unsigned int _index, const math::Angle &_angle)
- Removed virtual void SetLowStop(unsigned int _index, const math::Angle &_angle)
- Replacement virtual bool SetLowStop(unsigned int _index, const math::Angle &_angle)
-
gazebo/physics/ode/ODEUniversalJoint.hh
- Removed virtual void SetHighStop(unsigned int _index, const math::Angle &_angle)
- Replacement virtual bool SetHighStop(unsigned int _index, const math::Angle &_angle)
- Removed virtual void SetLowStop(unsigned int _index, const math::Angle &_angle)
- Replacement virtual bool SetLowStop(unsigned int _index, const math::Angle &_angle)
-
gazebo/physics/simbody/SimbodyJoint.hh
- Removed virtual void SetHighStop(unsigned int _index, const math::Angle &_angle)
- Replacement virtual bool SetHighStop(unsigned int _index, const math::Angle &_angle)
- Removed virtual void SetLowStop(unsigned int _index, const math::Angle &_angle)
- Replacement virtual bool SetLowStop(unsigned int _index, const math::Angle &_angle)
-
gazebo/physics/simbody/SimbodyScrewJoint.hh
- Removed virtual void SetHighStop(unsigned int _index, const math::Angle &_angle)
- Replacement virtual bool SetHighStop(unsigned int _index, const math::Angle &_angle)
- Removed virtual void SetLowStop(unsigned int _index, const math::Angle &_angle)
- Replacement virtual bool SetLowStop(unsigned int _index, const math::Angle &_angle)
-
gazebo/physics/Joint.hh
- bool FindAllConnectedLinks(const LinkPtr &_originalParentLink, Link_V &_connectedLinks);
- math::Pose ComputeChildLinkPose( unsigned int _index, double _position);
-
gazebo/physics/Link.hh
- void MoveFrame(const math::Pose &_worldReferenceFrameSrc, const math::Pose &_worldReferenceFrameDst);
- bool FindAllConnectedLinksHelper( const LinkPtr &_originalParentLink, Link_V &_connectedLinks, bool _fistLink = false);
- bool ContainsLink(const Link_V &_vector, const LinkPtr &_value);
-
gazebo/physics/Collision.hh
- void SetWorldPoseDirty()
- virtual const math::Pose &GetWorldPose() const
-
gazebo/physics/JointController.hh
- common::Time GetLastUpdateTime() const
- std::map<std::string, JointPtr> GetJoints() const
- bool SetPositionTarget(const std::string &_jointName, double _target)
- bool SetVelocityTarget(const std::string &_jointName, double _target)
- std::map<std::string, common::PID> GetPositionPIDs() const
- std::map<std::string, common::PID> GetVelocityPIDs() const
- std::map<std::string, double> GetForces() const
- std::map<std::string, double> GetPositions() const
- std::map<std::string, double> GetVelocities() const
-
gazebo/common/PID.hh
- double GetPGain() const
- double GetIGain() const
- double GetDGain() const
- double GetIMax() const
- double GetIMin() const
- double GetCmdMax() const
- double GetCmdMin() const
-
gazebo/transport/TransportIface.hh
- transport::ConnectionPtr connectToMaster()
-
gazebo/physics/World.hh
- msgs::Scene GetSceneMsg() const
-
gazebo/physics/ContactManager.hh
- unsigned int GetFilterCount()
- bool HasFilter(const std::string &_name)
- void RemoveFilter(const std::string &_name)
-
gazebo/physics/Joint.hh
- virtual void Fini()
- math::Pose GetAnchorErrorPose() const
- math::Quaternion GetAxisFrame(unsigned int _index) const
- double GetWorldEnergyPotentialSpring(unsigned int _index) const
- math::Pose GetParentWorldPose() const
- double GetSpringReferencePosition(unsigned int) const
- math::Pose GetWorldPose() const
- virtual void SetEffortLimit(unsigned _index, double _stiffness)
- virtual void SetStiffness(unsigned int _index, double _stiffness) = 0
- virtual void SetStiffnessDamping(unsigned int _index, double _stiffness, double _damping, double _reference = 0) = 0
- bool axisParentModelFrame[MAX_JOINT_AXIS]
- protected: math::Pose parentAnchorPose
- public: double GetInertiaRatio(const math::Vector3 &_axis) const
-
gazebo/physics/Link.hh
- double GetWorldEnergy() const
- double GetWorldEnergyKinetic() const
- double GetWorldEnergyPotential() const
- bool initialized
-
gazebo/physics/Model.hh
- double GetWorldEnergy() const
- double GetWorldEnergyKinetic() const
- double GetWorldEnergyPotential() const
-
gazebo/physics/SurfaceParams.hh
- FrictionPyramid()
- ~FrictionPyramid()
- double GetMuPrimary()
- double GetMuSecondary()
- void SetMuPrimary(double _mu)
- void SetMuSecondary(double _mu)
- math::Vector3 direction1
- Note: Replaces mu, m2, fdir1 variables
-
gazebo/physics/bullet/BulletSurfaceParams.hh
- BulletSurfaceParams()
- virtual ~BulletSurfaceParams()
- virtual void Load(sdf::ElementPtr _sdf)
- virtual void FillMsg(msgs::Surface &_msg)
- virtual void ProcessMsg(msgs::Surface &_msg)
- FrictionPyramid frictionPyramid
-
gazebo/physics/ode/ODESurfaceParams.hh
- virtual void FillMsg(msgs::Surface &_msg)
- virtual void ProcessMsg(msgs::Surface &_msg)
- double bounce
- double bounce
- double bounceThreshold
- double kp
- double kd
- double cfm
- double erp
- double maxVel
- double minDepth
- FrictionPyramid frictionPyramid
- double slip1
- double slip2
-
gazebo/rendering/Light.hh
- bool GetVisible() const
- virtual void LoadFromMsg(const msgs::Light &_msg)
-
gazebo/sensors/ForceTorqueSensor.hh
- physics::JointPtr GetJoint() const
-
gazebo/sensors/Noise.hh
- virtual double ApplyImpl(double _in)
- virtual void Fini()
- virtual void SetCustomNoiseCallback(boost::function<double (double)> _cb)
-
gazebo/sensors/Sensor.hh
- NoisePtr GetNoise(unsigned int _index = 0) const
-
gazebo/sensors/GaussianNoiseModel.hh
-
gazebo/physics/ode/ODEUniversalJoint.hh
- virtual void SetHighStop(unsigned int _index, const math::Angle &_angle)
- virtual void SetLowStop(unsigned int _index, const math::Angle &_angle)
- virtual void SetAttribute(const std::string &_key, unsigned int _index, const boost::any &_value)
- virtual double GetAttribute(const std::string &_key, unsigned int _index)
-
gazebo/physics/simbody/SimbodyScrewJoint.hh
- virtual void SetThreadPitch(double _threadPitch)
- virtual void GetThreadPitch()
-
gazebo/physics/ode/ODEScrewJoint.hh
- virtual void SetThreadPitch(double _threadPitch)
- virtual void GetThreadPitch()
-
gazebo/physics/ScrewJoint.hh
- virtual math::Vector3 GetAnchor(unsigned int _index) const
- virtual void SetAnchor(unsigned int _index, const math::Vector3 &_anchor)
-
gazebo/physics/bullet/BulletJoint.hh
- virtual math::Angle GetHighStop(unsigned int _index)
- virtual math::Angle GetLowStop(unsigned int _index)
-
gazebo/physics/simbody/SimbodyPhysics.hh
- virtual boost::any GetParam(const std::string &_key) const
- virtual bool SetParam(const std::string &_key, const boost::any &_value)
-
gazebo/physics/dart/DARTPhysics.hh
- virtual boost::any GetParam(const std::string &_key) const
- virtual bool SetParam(const std::string &_key, const boost::any &_value)
-
gazebo/physics/Joint.hh
- math::Quaternion GetAxisFrameOffset(unsigned int _index) const
-
Removed libtool
- Libtool used to be an option for loading plugins. Now, only libdl is supported.
-
gazebo/physics/Base.hh
- Base_V::iterator childrenEnd
-
gazebo/sensors/Noise.hh
- double Noise::GetMean() const
- double Noise::GetStdDev() const
- double Noise::GetBias() const
- Note: Moved gaussian noise functions to a new GaussianNoiseModel class
-
gazebo/physics/SurfaceParams.hh
- double bounce
- double bounce
- double bounceThreshold
- double kp
- double kd
- double cfm
- double erp
- double maxVel
- double minDepth
- double mu1
- double mu2
- double slip1
- double slip2
- math::Vector3 fdir1
- Note: These parameters were moved to FrictionPyramid, ODESurfaceParams, and BulletSurfaceParams.
- gazebo/gazebo.hh
- Deprecation void fini()
- Deprecation void stop()
- Replacement bool shutdown()
- Note Replace fini and stop with shutdown
- Deprecation bool load()
- Deprecation bool init()
- Deprecation bool run()
- Replacement bool setupClient()
- Use this function to setup gazebo for use as a client
- Replacement bool setupServer()
- Use this function to setup gazebo for use as a server
- Note Replace load+init+run with setupClient/setupServer
- Deprecation std::string find_file(const std::string &_file)
- Replacement std::string common::find_file(const std::string &_file)
- Deprecation void add_plugin(const std::string &_filename)
- Replacement void addPlugin(const std::string &_filename)
- Deprecation void print_version()
- Replacement void printVersion()
- gazebo/physics/World.hh
- Deprecation void World::StepWorld(int _steps)
- Replacement void World::Step(unsigned int _steps)
- gazebo/sensors/SensorsIface.hh
- Deprecation std::string sensors::create_sensor(sdf::ElementPtr _elem, const std::string &_worldName,const std::string &_parentName)
- Replacement std::string sensors::create_sensor(sdf::ElementPtr _elem, const std::string &_worldName, const std::string &_parentName, uint32_t _parentId)
- gazebo/sensors/Sensor.hh
- Deprecation void Sensor::SetParent(const std::string &_name)
- Replacement void Sensor::SetParent(const std::string &_name, uint32_t _id)
- gazebo/sensors/SensorManager.hh
- Deprecation std::string CreateSensor(sdf::ElementPtr _elem, const std::string &_worldName, const std::string &_parentName)
- Replacement std::string CreateSensor(sdf::ElementPtr _elem, const std::string &_worldName, const std::string &_parentName, uint32_t _parentId)
- gazebo/sensors/Collision.hh
- Deprecation void Collision::SetContactsEnabled(bool _enable)
- Replacement Use ContactManager.
- Deprecation bool Colliion::GetContactsEnabled() const
- Replacement Use ContactManager.
- Deprecation void AddContact(const Contact &_contact)
- Replacement Use ContactManager.
- File rename:
gazebo/common/Common.hh
togazebo/common/CommonIface.hh
- File rename:
gazebo/physics/Physics.hh
togazebo/physics/PhysicsIface.hh
- File rename:
gazebo/rendering/Rendering.hh
togazebo/rendering/RenderingIface.hh
- File rename:
gazebo/sensors/Sensors.hh
togazebo/sensors/SensorsIface.hh
- File rename:
gazebo/transport/Transport.hh
togazebo/transport/TransportIface.hh
- File rename:
gazebo/gui/Gui.hh
togazebo/gui/GuiIface.hh
- File rename:
<model>/manifest.xml
to<model>/model.config
- File rename:
<model_database>/manifest.xml
to<model_database>/database.config
- gazebo/msgs/physics.proto
- Removed optional double dt
- Replacement optional double min_step_size
- Removed optional double update_rate
- Replacement optional double real_time_update_rate
- gazebo/physics/ModelState.hh
- Removed LinkState ModelState::GetLinkState(int _index)
API change
- Replacement LinkState ModelState::GetLinkState(const std::string &_linkName) const
- Removed LinkState ModelState::GetLinkState(int _index)
- gazebo/physics/PhyscisEngine.hh
- Removed void PhysicsEngine::SetUpdateRate(double _value)
API change
- Replacement void PhyscisEngine::SetRealTimeUpdateRate(double _rate)
- Removed double PhysicsEngine::GetUpdateRate()
API change
- Replacement double PhysicsEngine::GetRealTimeUpdateRate() const
- Removed void PhysicsEngine::SetStepTime(double _value)
API change
- Replacement void PhysicsEngine::SetMaxStepSize(double _stepSize)
- Removed double PhysicsEngine::GetStepTime()
API change
- Replacement double PhysicsEngine::GetMaxStepSize() const
- Removed void PhysicsEngine::SetUpdateRate(double _value)
- gazebo/physics/Joint.hh
- Removed: Joint::Load(LinkPtr _parent, LinkPtr _child, const math::Vector3 &_pos)
API chance
- Replacement: Joint::Load(LinkPtr _parent, LinkPtr _child, const math::Pose &_pose)
- Removed: public: double GetInertiaRatio(unsigned int _index) const
- Replacement: public: double GetInertiaRatio(const unsigned int _index) const
- Removed: Joint::Load(LinkPtr _parent, LinkPtr _child, const math::Vector3 &_pos)
- gazebo/common/Events.hh
- Removed: Events::ConnectWorldUpdateStart(T _subscriber)
API change
- Replacement ConnectionPtr Events::ConnectWorldUpdateBegin(T _subscriber)
- Removed: Events::DisconnectWorldUpdateStart(T _subscriber)
API change
- Replacement ConnectionPtr Events::DiconnectWorldUpdateBegin(T _subscriber)
- Removed: Events::ConnectWorldUpdateStart(T _subscriber)
- gazebo/physics/Link.hh
- Removed void Link::RemoveChildJoint(JointPtr _joint)
API change
- Replacement void Link::RemoveChildJoint(const std::string &_jointName)
- Removed void Link::RemoveParentJoint(const std::string &_jointName)
API change
- Replacement void Link::RemoveParentJoint(const std::string &_jointName)
- Removed void Link::RemoveChildJoint(JointPtr _joint)
- gazebo/physics/MeshShape.hh
- Removed std::string MeshShape::GetFilename() const
API change
- Replacement std::string MeshShape::GetURI() const
- Removed void MeshShape::SetFilename() const
API change
- Replacement std::string MeshShape::SetMesh(const std::string &_uri, const std::string &_submesh = "", bool _center = false) const
- Removed std::string MeshShape::GetFilename() const
- gazebo/common/Time.hh
- Removed static Time::NSleep(Time _time)
API change
- Replacement static Time NSleep(unsigned int _ns)
- Removed static Time::NSleep(Time _time)
- gazebo/physics/Collision.hh
- template event::ConnectionPtr ConnectContact(T _subscriber)
- template event::ConnectionPtr DisconnectContact(T _subscriber)
- Note: The ContactManager::CreateFilter functions can be used to create a gazebo topic with contact messages filtered by the name(s) of collision shapes. The topic can then be subscribed with a callback to replicate this removed functionality. See gazebo pull request #713 for an example migration.