clamping.cpp
Go to the documentation of this file.
00001 #include <canopen_402/motor.h>
00002 #include <gtest/gtest.h>
00003 
00004 
00005 template<typename T> class ModeTargetHelperTest : public canopen::ModeTargetHelper<T>, public ::testing::Test{
00006 public:
00007     ModeTargetHelperTest() : canopen::ModeTargetHelper<T>(0) {}
00008     virtual bool read(const uint16_t &sw) { return false; }
00009     virtual bool write(canopen::Mode::OpModeAccesser& cw) { return false; }
00010 };
00011 
00012 typedef ::testing::Types<uint8_t, int8_t, uint16_t, int16_t, uint32_t, int32_t, uint64_t, int64_t> MyTypes;
00013 
00014 TYPED_TEST_CASE(ModeTargetHelperTest, MyTypes);
00015 
00016 TYPED_TEST(ModeTargetHelperTest, CheckNaN){
00017     ASSERT_FALSE(this->setTarget(std::numeric_limits<double>::quiet_NaN()));
00018 }
00019 
00020 TYPED_TEST(ModeTargetHelperTest, CheckZero){
00021     ASSERT_TRUE(this->setTarget(0.0));
00022 }
00023 
00024 TYPED_TEST(ModeTargetHelperTest, CheckOne){
00025     ASSERT_TRUE(this->setTarget(1.0));
00026 }
00027 
00028 TYPED_TEST(ModeTargetHelperTest, CheckMax){
00029     double max = static_cast<double>(std::numeric_limits<TypeParam>::max());
00030 
00031     ASSERT_TRUE(this->setTarget(max));
00032     ASSERT_EQ(max, this->getTarget());
00033 
00034     ASSERT_TRUE(this->setTarget(max-1));
00035     ASSERT_EQ(max-1,this->getTarget());
00036 
00037     ASSERT_TRUE(this->setTarget(max+1));
00038     ASSERT_EQ(max, this->getTarget());
00039 }
00040 
00041 TYPED_TEST(ModeTargetHelperTest, CheckMin){
00042     double min = static_cast<double>(std::numeric_limits<TypeParam>::min());
00043 
00044     ASSERT_TRUE(this->setTarget(min));
00045     ASSERT_EQ(min, this->getTarget());
00046 
00047     ASSERT_TRUE(this->setTarget(min-1));
00048     ASSERT_EQ(min, this->getTarget());
00049 
00050     ASSERT_TRUE(this->setTarget(min+1));
00051     ASSERT_EQ(min+1,this->getTarget());
00052 }
00053 
00054 int main(int argc, char **argv){
00055   testing::InitGoogleTest(&argc, argv);
00056   return RUN_ALL_TESTS();
00057 }


canopen_402
Author(s): Thiago de Freitas , Mathias Lüdtke
autogenerated on Sun Sep 3 2017 03:10:49