cartesian_state_interface_test.cpp
Go to the documentation of this file.
1 // -- BEGIN LICENSE BLOCK ----------------------------------------------
2 // Copyright 2020 FZI Forschungszentrum Informatik
3 // Created on behalf of Universal Robots A/S
4 //
5 // Licensed under the Apache License, Version 2.0 (the "License");
6 // you may not use this file except in compliance with the License.
7 // You may obtain a copy of the License at
8 //
9 // http://www.apache.org/licenses/LICENSE-2.0
10 //
11 // Unless required by applicable law or agreed to in writing, software
12 // distributed under the License is distributed on an "AS IS" BASIS,
13 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 // See the License for the specific language governing permissions and
15 // limitations under the License.
16 // -- END LICENSE BLOCK ------------------------------------------------
17 
18 //----------------------------------------------------------------------
25 //----------------------------------------------------------------------
26 
27 #include <gtest/gtest.h>
28 
30 
31 using namespace ros_controllers_cartesian;
32 
33 TEST(CartesianStateHandleTest, TestConstructor)
34 {
35  std::string reference_frame = "base";
36  std::string controlled_frame = "tool0";
37  geometry_msgs::Pose pose_buffer;
38  geometry_msgs::Twist twist_buffer;
39  geometry_msgs::Accel accel_buffer;
40  geometry_msgs::Accel jerk_buffer;
41 
42  EXPECT_NO_THROW(CartesianStateHandle obj(reference_frame, controlled_frame, &pose_buffer, &twist_buffer,
43  &accel_buffer, &jerk_buffer));
44  EXPECT_THROW(
45  CartesianStateHandle obj(reference_frame, controlled_frame, nullptr, &twist_buffer, &accel_buffer, &jerk_buffer),
47  EXPECT_THROW(
48  CartesianStateHandle obj(reference_frame, controlled_frame, &pose_buffer, nullptr, &accel_buffer, &jerk_buffer),
50  EXPECT_THROW(
51  CartesianStateHandle obj(reference_frame, controlled_frame, &pose_buffer, &twist_buffer, nullptr, &jerk_buffer),
53  EXPECT_THROW(
54  CartesianStateHandle obj(reference_frame, controlled_frame, &pose_buffer, &twist_buffer, &accel_buffer, nullptr),
56 }
57 
58 int main(int argc, char** argv)
59 {
60  testing::InitGoogleTest(&argc, argv);
61  return RUN_ALL_TESTS();
62 }
ros_controllers_cartesian
Definition: cartesian_command_interface.h:31
ros_controllers_cartesian::CartesianStateHandle
A state handle for Cartesian hardware interfaces.
Definition: cartesian_state_handle.h:48
main
int main(int argc, char **argv)
Definition: cartesian_state_interface_test.cpp:58
hardware_interface::HardwareInterfaceException
TEST
TEST(CartesianStateHandleTest, TestConstructor)
Definition: cartesian_state_interface_test.cpp:33
cartesian_state_handle.h


cartesian_interface
Author(s):
autogenerated on Tue Oct 15 2024 02:09:12