trajectory_time.cc
Go to the documentation of this file.
1 /*
2  * This file is part of the rc_dynamics_api package.
3  *
4  * Copyright (c) 2017 Roboception GmbH
5  * All rights reserved
6  *
7  * Author: Christian Emmerich
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions are met:
11  *
12  * 1. Redistributions of source code must retain the above copyright notice,
13  * this list of conditions and the following disclaimer.
14  *
15  * 2. Redistributions in binary form must reproduce the above copyright notice,
16  * this list of conditions and the following disclaimer in the documentation
17  * and/or other materials provided with the distribution.
18  *
19  * 3. Neither the name of the copyright holder nor the names of its contributors
20  * may be used to endorse or promote products derived from this software without
21  * specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
24  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
25  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
26  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
27  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
28  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
29  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
30  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
31  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
32  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  */
35 
36 #include "trajectory_time.h"
37 
38 #include <stdexcept>
39 
40 namespace rc
41 {
42 TrajectoryTime TrajectoryTime::Absolute(unsigned long sec, unsigned long nsec)
43 {
44  return TrajectoryTime(sec, nsec, false);
45 }
46 
47 TrajectoryTime TrajectoryTime::RelativeToStart(unsigned long sec, unsigned long nsec)
48 {
49  return TrajectoryTime(sec, nsec, true);
50 }
51 
52 TrajectoryTime TrajectoryTime::RelativeToEnd(unsigned long sec, unsigned long nsec)
53 {
54  return TrajectoryTime(-sec, -nsec, true);
55 }
56 
57 TrajectoryTime::TrajectoryTime(long sec, long nsec, bool relative) : relative_(relative), sec_(sec), nsec_(nsec)
58 {
59  if (!relative && (sec < 0 || nsec < 0))
60  {
61  throw std::invalid_argument("Negative values for sec or nsec are only allowed for relative time specification!");
62  }
63 }
64 }
rc
Definition: data_receiver.h:61
trajectory_time.h
rc::TrajectoryTime::TrajectoryTime
TrajectoryTime(long sec, long nsec, bool relative)
Full constructor for specifiying a time either as relative offset or as absolute timestamp.
Definition: trajectory_time.cc:57
rc::TrajectoryTime
Represents a time stamp to query the trajectory of rcvisard's slam module.
Definition: trajectory_time.h:56
rc::TrajectoryTime::Absolute
static TrajectoryTime Absolute(unsigned long sec, unsigned long nsec)
Creates an absolute time stamp of the given values.
Definition: trajectory_time.cc:42
rc::TrajectoryTime::RelativeToEnd
static TrajectoryTime RelativeToEnd(unsigned long sec=0, unsigned long nsec=0)
Creates a time stamp from the given values as an offset from the end point of the trajectory.
Definition: trajectory_time.cc:52
rc::TrajectoryTime::RelativeToStart
static TrajectoryTime RelativeToStart(unsigned long sec=0, unsigned long nsec=0)
Creates a time stamp from the given values as an offset to the start point of the trajectory.
Definition: trajectory_time.cc:47


rc_dynamics_api
Author(s): Heiko Hirschmueller , Christian Emmerich , Felix Endres
autogenerated on Wed Mar 2 2022 00:48:50