00001 /* 00002 * This file is part of the rc_dynamics_api package. 00003 * 00004 * Copyright (c) 2017 Roboception GmbH 00005 * All rights reserved 00006 * 00007 * Author: Christian Emmerich 00008 * 00009 * Redistribution and use in source and binary forms, with or without 00010 * modification, are permitted provided that the following conditions are met: 00011 * 00012 * 1. Redistributions of source code must retain the above copyright notice, 00013 * this list of conditions and the following disclaimer. 00014 * 00015 * 2. Redistributions in binary form must reproduce the above copyright notice, 00016 * this list of conditions and the following disclaimer in the documentation 00017 * and/or other materials provided with the distribution. 00018 * 00019 * 3. Neither the name of the copyright holder nor the names of its contributors 00020 * may be used to endorse or promote products derived from this software without 00021 * specific prior written permission. 00022 * 00023 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00024 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00025 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00026 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE 00027 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00028 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00029 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00030 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00031 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00032 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 * POSSIBILITY OF SUCH DAMAGE. 00034 */ 00035 00036 #include "trajectory_time.h" 00037 00038 #include <stdexcept> 00039 00040 namespace rc 00041 { 00042 TrajectoryTime TrajectoryTime::Absolute(unsigned long sec, unsigned long nsec) 00043 { 00044 return TrajectoryTime(sec, nsec, false); 00045 } 00046 00047 TrajectoryTime TrajectoryTime::RelativeToStart(unsigned long sec, unsigned long nsec) 00048 { 00049 return TrajectoryTime(sec, nsec, true); 00050 } 00051 00052 TrajectoryTime TrajectoryTime::RelativeToEnd(unsigned long sec, unsigned long nsec) 00053 { 00054 return TrajectoryTime(-sec, -nsec, true); 00055 } 00056 00057 TrajectoryTime::TrajectoryTime(long sec, long nsec, bool relative) : relative_(relative), sec_(sec), nsec_(nsec) 00058 { 00059 if (!relative && (sec < 0 || nsec < 0)) 00060 { 00061 throw std::invalid_argument("Negative values for sec or nsec are only allowed for relative time specification!"); 00062 } 00063 } 00064 }