Segment.h
Go to the documentation of this file.
1 /*
2  * This file is part of ArmarX.
3  *
4  * ArmarX is free software; you can redistribute it and/or modify
5  * it under the terms of the GNU General Public License version 2 as
6  * published by the Free Software Foundation.
7  *
8  * ArmarX is distributed in the hope that it will be useful, but
9  * WITHOUT ANY WARRANTY; without even the implied warranty of
10  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11  * GNU General Public License for more details.
12  *
13  * You should have received a copy of the GNU General Public License
14  * along with this program. If not, see <http://www.gnu.org/licenses/>.
15  *
16  * @author Fabian Reister ( fabian dot reister at kit dot edu )
17  * @date 2021
18  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
19  * GNU General Public License
20  */
21 
22 #pragma once
23 
24 // STD / STL
25 #include <string>
26 #include <optional>
27 #include <unordered_map>
28 
29 // Eigen
30 #include <Eigen/Geometry>
31 
32 // ArmarX
36 
37 #include <RobotAPI/libraries/armem_robot_state/aron/Transform.aron.generated.h>
39 
40 
42 {
44  {
46 
47  public:
48 
50  virtual ~Segment() override;
51 
52  void defineProperties(armarx::PropertyDefinitionsPtr defs, const std::string& prefix = "") override;
53 
54  void init() override;
55 
56  void onConnect();
57 
58 
59  RobotPoseMap getRobotGlobalPoses(const armem::Time& timestamp) const;
60  RobotPoseMap getRobotGlobalPosesLocking(const armem::Time& timestamp) const;
61 
62  RobotFramePoseMap getRobotFramePoses(const armem::Time& timestamp) const;
64 
67 
68 
69  private:
70 
71  EntityUpdate makeUpdate(const armem::robot_state::Transform& transform) const;
72 
73  PredictionResult predictLinear(const PredictionRequest& request);
74 
75  struct Properties
76  {
77  double predictionTimeWindow = 2;
78  };
79  Properties properties;
80 
81  };
82 
83 } // namespace armarx::armem::server::robot_state::localization
armarx::armem::PredictionRequest
Definition: Prediction.h:49
armarx::armem::server::segment::SpecializedCoreSegment
A base class for core segments.
Definition: SpecializedCoreSegment.h:20
armarx::armem::server::robot_state::localization::Segment::~Segment
virtual ~Segment() override
Definition: Segment.cpp:42
armarx::armem::server::MemoryToIceAdapter
Helps connecting a Memory server to the Ice interface.
Definition: MemoryToIceAdapter.h:19
forward_declarations.h
armarx::armem::server::robot_state::localization::Segment
Definition: Segment.h:43
armarx::armem::server::robot_state::localization::Segment::Segment
Segment(server::MemoryToIceAdapter &iceMemory)
Definition: Segment.cpp:36
armarx::armem::server::robot_state::localization
Definition: forward_declarations.h:68
armarx::armem::PredictionResult
Definition: Prediction.h:58
armarx::armem::server::robot_state::localization::Segment::commitTransformLocking
bool commitTransformLocking(const armem::robot_state::Transform &transform)
Definition: Segment.cpp:173
armarx::armem::server::robot_state::localization::Segment::defineProperties
void defineProperties(armarx::PropertyDefinitionsPtr defs, const std::string &prefix="") override
Definition: Segment.cpp:46
armarx::armem::server::robot_state::localization::RobotPoseMap
std::unordered_map< std::string, Eigen::Affine3f > RobotPoseMap
Definition: forward_declarations.h:70
forward_declarations.h
armarx::armem::server::robot_state::localization::Segment::onConnect
void onConnect()
Definition: Segment.cpp:65
armarx::armem::server::segment::detail::SegmentBase< server::wm::CoreSegment >
armarx::armem::server::robot_state::localization::Segment::getRobotGlobalPosesLocking
RobotPoseMap getRobotGlobalPosesLocking(const armem::Time &timestamp) const
Definition: Segment.cpp:117
armarx::armem::server::robot_state::localization::Segment::getRobotGlobalPoses
RobotPoseMap getRobotGlobalPoses(const armem::Time &timestamp) const
Definition: Segment.cpp:127
armarx::armem::robot_state::Transform
Definition: types.h:41
armarx::armem::EntityUpdate
An update of an entity for a specific point in time.
Definition: Commit.h:27
armarx::core::time::DateTime
Represents a point in time.
Definition: DateTime.h:24
armarx::armem::server::segment::detail::SegmentBase< server::wm::CoreSegment >::iceMemory
MemoryToIceAdapter & iceMemory
Definition: SpecializedSegment.h:60
armarx::armem::server::robot_state::localization::Segment::getRobotFramePosesLocking
RobotFramePoseMap getRobotFramePosesLocking(const armem::Time &timestamp) const
Definition: Segment.cpp:71
armarx::armem::server::robot_state::localization::Segment::commitTransform
bool commitTransform(const armem::robot_state::Transform &transform)
Definition: Segment.cpp:163
IceUtil::Handle< class PropertyDefinitionContainer >
armarx::transform
auto transform(const Container< InputT, Alloc > &in, OutputT(*func)(InputT const &)) -> Container< OutputT, typename std::allocator_traits< Alloc >::template rebind_alloc< OutputT > >
Convenience function (with less typing) to transform a container of type InputT into the same contain...
Definition: algorithm.h:315
armarx::armem::server::robot_state::localization::RobotFramePoseMap
std::unordered_map< std::string, std::vector< Eigen::Affine3f > > RobotFramePoseMap
Definition: forward_declarations.h:71
SpecializedProviderSegment.h
armarx::armem::server::robot_state::localization::Segment::init
void init() override
Definition: Segment.cpp:56
SpecializedCoreSegment.h
armarx::armem::server::robot_state::localization::Segment::getRobotFramePoses
RobotFramePoseMap getRobotFramePoses(const armem::Time &timestamp) const
Definition: Segment.cpp:81