├── README.md └── ros_control_example ├── config ├── joint_limits.yaml └── controllers.yaml ├── launch ├── check_urdf.launch ├── check_position_controller.launch └── check_velocity_controller.launch ├── scripts └── joints_receive_from_arduino.py ├── include └── ros_control_example │ └── robot_hardware_interface.h ├── urdf └── single_joint_actuator.urdf.xacro ├── src ├── arduino_code │ └── arduino_code.ino └── robot_hardware_interface_node.cpp ├── package.xml └── CMakeLists.txt /README.md: -------------------------------------------------------------------------------- 1 | # ros_control_example 2 | Position and velocity control of a DC motor using ros_control package 3 | -------------------------------------------------------------------------------- /ros_control_example/config/joint_limits.yaml: -------------------------------------------------------------------------------- 1 | joint_limits: 2 | joint1: 3 | has_position_limits: false 4 | min_position: 0 5 | max_position: 0 6 | has_velocity_limits: true 7 | max_velocity: 1.0472 8 | has_acceleration_limits: false 9 | max_acceleration: 0.0 10 | has_jerk_limits: false 11 | max_jerk: 0 12 | has_effort_limits: true 13 | max_effort: 255 14 | min_effort: -255 15 | 16 | -------------------------------------------------------------------------------- /ros_control_example/launch/check_urdf.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /ros_control_example/scripts/joints_receive_from_arduino.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | import rospy 3 | from rospy_tutorials.msg import Floats 4 | from three_dof_planar_manipulator.srv import Floats_array, Floats_arrayResponse, Floats_arrayRequest 5 | pos=0 6 | vel=0 7 | 8 | def my_callback(msg): 9 | global pos, vel 10 | pos=msg.data[0] 11 | vel=msg.data[1] 12 | #print "Pos: ", pos, "vel: ", vel 13 | 14 | def my_server(req): 15 | global pos, vel 16 | res = Floats_arrayResponse() 17 | res.res=[pos, vel] 18 | return res 19 | 20 | rospy.init_node('subscriber_py') #initialzing the node with name "subscriber_py" 21 | 22 | rospy.Subscriber("/joint_states_from_arduino", Floats, my_callback, queue_size=10) 23 | 24 | rospy.Service('/read_joint_state', Floats_array, my_server) 25 | 26 | rospy.spin() 27 | -------------------------------------------------------------------------------- /ros_control_example/config/controllers.yaml: -------------------------------------------------------------------------------- 1 | single_joint_actuator: 2 | # Publish all joint states ----------------------------------- 3 | joints_update: 4 | type: joint_state_controller/JointStateController 5 | publish_rate: 50 6 | 7 | # Position Controllers --------------------------------------- 8 | joint1_position_controller: 9 | type: effort_controllers/JointPositionController 10 | joint: joint1 11 | pid: {p: 1300.0, i: 0.0, d: 5, i_clamp_min: -130.0, i_clamp_max: 130, antiwindup: True} 12 | 13 | # Velocity Controllers --------------------------------------- 14 | joint1_velocity_controller: 15 | type: effort_controllers/JointVelocityController 16 | joint: joint1 17 | pid: {p: 100.0, i: 100.0, d: 0.0, i_clamp_min: -255.0, i_clamp_max: 255, antiwindup: True} 18 | -------------------------------------------------------------------------------- /ros_control_example/launch/check_position_controller.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 27 | 28 | -------------------------------------------------------------------------------- /ros_control_example/launch/check_velocity_controller.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 27 | 28 | -------------------------------------------------------------------------------- /ros_control_example/include/ros_control_example/robot_hardware_interface.h: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include 11 | #include 12 | #include 13 | #include 14 | 15 | class ROBOTHardwareInterface : public hardware_interface::RobotHW 16 | { 17 | public: 18 | ROBOTHardwareInterface(ros::NodeHandle& nh); 19 | ~ROBOTHardwareInterface(); 20 | void init(); 21 | void update(const ros::TimerEvent& e); 22 | void read(); 23 | void write(ros::Duration elapsed_time); 24 | ros::Publisher pub; 25 | ros::ServiceClient client; 26 | rospy_tutorials::Floats joints_pub; 27 | three_dof_planar_manipulator::Floats_array joint_read; 28 | 29 | protected: 30 | hardware_interface::JointStateInterface joint_state_interface_; 31 | hardware_interface::PositionJointInterface position_joint_interface_; 32 | hardware_interface::EffortJointInterface effort_joint_interface_; 33 | 34 | 35 | joint_limits_interface::EffortJointSaturationInterface effortJointSaturationInterface; 36 | 37 | int num_joints_; 38 | std::string joint_name_; 39 | double joint_position_; 40 | double joint_velocity_; 41 | double joint_effort_; 42 | double joint_position_command_; 43 | double joint_effort_command_; 44 | double joint_velocity_command_; 45 | 46 | ros::NodeHandle nh_; 47 | ros::Timer non_realtime_loop_; 48 | ros::Duration elapsed_time_; 49 | double loop_hz_; 50 | boost::shared_ptr controller_manager_; 51 | }; 52 | 53 | -------------------------------------------------------------------------------- /ros_control_example/urdf/single_joint_actuator.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | 67 | 68 | 69 | 70 | 71 | 72 | 73 | 74 | 75 | 76 | 77 | 78 | 79 | 80 | 81 | 82 | 83 | 84 | 85 | 86 | -------------------------------------------------------------------------------- /ros_control_example/src/arduino_code/arduino_code.ino: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #define encodPinA1 2 // Quadrature encoder A pin 4 | #define encodPinB1 8 // Quadrature encoder B pin 5 | #define M1 9 // PWM outputs to motor driver module 6 | #define M2 10 7 | 8 | ros::NodeHandle nh; 9 | 10 | double pos = 0, vel= 0, output = 0, temp=0; 11 | unsigned long lastTime,now,lasttimepub; 12 | volatile long encoderPos = 0,last_pos=0; 13 | rospy_tutorials::Floats joint_state; 14 | 15 | void set_angle_cb( const rospy_tutorials::Floats& cmd_msg){ 16 | output= cmd_msg.data[0]; 17 | } 18 | 19 | 20 | ros::Subscriber sub("/joints_to_aurdino", set_angle_cb); 21 | ros::Publisher pub("/joint_states_from_arduino", &joint_state); 22 | 23 | void setup(){ 24 | nh.initNode(); 25 | nh.subscribe(sub); 26 | nh.advertise(pub); 27 | pinMode(encodPinA1, INPUT_PULLUP); // quadrature encoder input A 28 | pinMode(encodPinB1, INPUT_PULLUP); // quadrature encoder input B 29 | attachInterrupt(0, encoder, FALLING); // update encoder position 30 | TCCR1B = TCCR1B & 0b11111000 | 1; // set 31KHz PWM to prevent motor noise 31 | } 32 | 33 | void loop(){ 34 | pos = (encoderPos*360)/2200 ; 35 | now = millis(); 36 | int timeChange = (now - lastTime); 37 | if(timeChange>=500 ) 38 | { 39 | temp = (360.0*1000*(encoderPos-last_pos)) /(2200.0*(now - lastTime)); 40 | if ((encoderPos < -2 || encoderPos > 2) && temp >= -60 && temp <=60 ) // to gaurd encoderPos at boundary i.e., after max limit it will rest. Then lastPos will be greater than encoderpos 41 | vel =temp; 42 | lastTime=now; 43 | last_pos=encoderPos; 44 | } 45 | 46 | pwmOut(output); 47 | 48 | if ((now - lasttimepub)> 100) 49 | { 50 | joint_state.data_length=2; 51 | joint_state.data[0]=pos; 52 | joint_state.data[1]=vel; 53 | pub.publish(&joint_state); 54 | lasttimepub=now; 55 | } 56 | 57 | nh.spinOnce(); 58 | 59 | } 60 | 61 | void encoder() { // pulse and direction, direct port reading to save cycles 62 | 63 | if (encoderPos > 2250 || encoderPos < -2250) 64 | encoderPos=0; 65 | if (PINB & 0b00000001) encoderPos++; // if(digitalRead(encodPinB1)==HIGH) count ++; 66 | else encoderPos--; // if(digitalRead(encodPinB1)==LOW) count --; 67 | } 68 | 69 | void pwmOut(float out) { 70 | if (out > 0) { 71 | analogWrite(M2, out); // drive motor CW 72 | analogWrite(M1, 0); 73 | } 74 | else { 75 | analogWrite(M2, 0); 76 | analogWrite(M1, abs(out)); // drive motor CCW 77 | } 78 | } 79 | -------------------------------------------------------------------------------- /ros_control_example/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | ros_control_example 4 | 0.0.0 5 | The ros_control_example package 6 | 7 | 8 | 9 | 10 | ubuntu 11 | 12 | 13 | 14 | 15 | 16 | TODO 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | catkin 52 | controller_manager 53 | roscpp 54 | rospy 55 | std_msgs 56 | std_srvs 57 | three_dof_planar_manipulator 58 | controller_manager 59 | roscpp 60 | rospy 61 | std_msgs 62 | std_srvs 63 | controller_manager 64 | roscpp 65 | rospy 66 | std_msgs 67 | std_srvs 68 | three_dof_planar_manipulator 69 | 70 | 71 | 72 | 73 | 74 | 75 | 76 | 77 | -------------------------------------------------------------------------------- /ros_control_example/src/robot_hardware_interface_node.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | ROBOTHardwareInterface::ROBOTHardwareInterface(ros::NodeHandle& nh) : nh_(nh) { 4 | init(); 5 | controller_manager_.reset(new controller_manager::ControllerManager(this, nh_)); 6 | loop_hz_=5; 7 | ros::Duration update_freq = ros::Duration(1.0/loop_hz_); 8 | 9 | pub = nh_.advertise("/joints_to_aurdino",10); 10 | client = nh_.serviceClient("/read_joint_state"); 11 | 12 | non_realtime_loop_ = nh_.createTimer(update_freq, &ROBOTHardwareInterface::update, this); 13 | } 14 | 15 | ROBOTHardwareInterface::~ROBOTHardwareInterface() { 16 | } 17 | 18 | void ROBOTHardwareInterface::init() { 19 | 20 | 21 | joint_name_="joint1"; 22 | 23 | // Create joint state interface 24 | hardware_interface::JointStateHandle jointStateHandle(joint_name_, &joint_position_, &joint_velocity_, &joint_effort_); 25 | joint_state_interface_.registerHandle(jointStateHandle); 26 | 27 | // Create position joint interface 28 | //hardware_interface::JointHandle jointPositionHandle(jointStateHandle, &joint_position_command_); 29 | //position_joint_interface_.registerHandle(jointPositionHandle); 30 | 31 | // Create velocity joint interface 32 | //hardware_interface::JointHandle jointVelocityHandle(jointStateHandle, &joint_velocity_command_); 33 | //effort_joint_interface_.registerHandle(jointVelocityHandle); 34 | 35 | // Create effort joint interface 36 | hardware_interface::JointHandle jointEffortHandle(jointStateHandle, &joint_effort_command_); 37 | effort_joint_interface_.registerHandle(jointEffortHandle); 38 | 39 | // Create Joint Limit interface 40 | joint_limits_interface::JointLimits limits; 41 | joint_limits_interface::getJointLimits("joint1", nh_, limits); 42 | joint_limits_interface::EffortJointSaturationHandle jointLimitsHandle(jointEffortHandle, limits); 43 | effortJointSaturationInterface.registerHandle(jointLimitsHandle); 44 | 45 | /* 46 | If you have more joints then, 47 | 48 | joint_name_= "joint2" 49 | 50 | // Create joint state interface 51 | hardware_interface::JointStateHandle jointStateHandle2(joint_name_, &joint_position_2, &joint_velocity_2, &joint_effort_2); 52 | joint_state_interface_.registerHandle(jointStateHandle); 53 | 54 | //create the position/velocity/effort interface according to your actuator 55 | hardware_interface::JointHandle jointPositionHandle2(jointStateHandle2, &joint_position_command_2); 56 | position_joint_interface_.registerHandle(jointPositionHandle2); 57 | 58 | hardware_interface::JointHandle jointVelocityHandle2(jointStateHandle2, &joint_velocity_command_2); 59 | effort_joint_interface_.registerHandle(jointVelocityHandle2); 60 | 61 | hardware_interface::JointHandle jointEffortHandle2(jointStateHandle2, &joint_effort_command_2); 62 | effort_joint_interface_.registerHandle(jointEffortHandle2); 63 | 64 | //create joint limit interface. 65 | joint_limits_interface::getJointLimits("joint2", nh_, limits); 66 | joint_limits_interface::EffortJointSaturationHandle jointLimitsHandle2(jointEffortHandle2, limits); 67 | effortJointSaturationInterface.registerHandle(jointLimitsHandle2); 68 | 69 | Repeat same for other joints 70 | */ 71 | 72 | 73 | // Register all joints interfaces 74 | registerInterface(&joint_state_interface_); 75 | registerInterface(&position_joint_interface_); 76 | registerInterface(&effort_joint_interface_); 77 | registerInterface(&effortJointSaturationInterface); 78 | } 79 | 80 | void ROBOTHardwareInterface::update(const ros::TimerEvent& e) { 81 | elapsed_time_ = ros::Duration(e.current_real - e.last_real); 82 | read(); 83 | controller_manager_->update(ros::Time::now(), elapsed_time_); 84 | write(elapsed_time_); 85 | } 86 | 87 | void ROBOTHardwareInterface::read() { 88 | 89 | joint_read.request.req=1.0; 90 | 91 | if(client.call(joint_read)) 92 | { 93 | joint_position_ = angles::from_degrees(joint_read.response.res[0]); 94 | joint_velocity_ = angles::from_degrees(joint_read.response.res[1]); 95 | ROS_INFO("Current Pos: %.2f, Vel: %.2f",joint_position_,joint_velocity_); 96 | /* 97 | if more than one joint, 98 | get values for joint_position_2, joint_velocity_2,...... 99 | */ 100 | 101 | } 102 | else 103 | { 104 | joint_position_ = 0; 105 | joint_velocity_ = 0; 106 | } 107 | 108 | 109 | } 110 | 111 | void ROBOTHardwareInterface::write(ros::Duration elapsed_time) { 112 | 113 | effortJointSaturationInterface.enforceLimits(elapsed_time); 114 | joints_pub.data.clear(); 115 | joints_pub.data.push_back(joint_effort_command_); 116 | 117 | /* 118 | if more than one joint, 119 | publish values for joint_effort_command_2,...... 120 | */ 121 | 122 | ROS_INFO("PWM Cmd: %.2f",joint_effort_command_); 123 | pub.publish(joints_pub); 124 | 125 | } 126 | 127 | 128 | 129 | int main(int argc, char** argv) 130 | { 131 | ros::init(argc, argv, "single_joint_hardware_interface"); 132 | ros::NodeHandle nh; 133 | //ros::AsyncSpinner spinner(4); 134 | ros::MultiThreadedSpinner spinner(2); // Multiple threads for controller service callback and for the Service client callback used to get the feedback from ardiuno 135 | ROBOTHardwareInterface ROBOT(nh); 136 | //spinner.start(); 137 | spinner.spin(); 138 | //ros::spin(); 139 | return 0; 140 | } 141 | -------------------------------------------------------------------------------- /ros_control_example/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(ros_control_example) 3 | 4 | ## Compile as C++11, supported in ROS Kinetic and newer 5 | # add_compile_options(-std=c++11) 6 | 7 | ## Find catkin macros and libraries 8 | ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) 9 | ## is used, also find other catkin packages 10 | find_package(catkin REQUIRED COMPONENTS 11 | controller_manager 12 | roscpp 13 | rospy 14 | std_msgs 15 | std_srvs 16 | three_dof_planar_manipulator 17 | ) 18 | 19 | ## System dependencies are found with CMake's conventions 20 | # find_package(Boost REQUIRED COMPONENTS system) 21 | 22 | 23 | ## Uncomment this if the package has a setup.py. This macro ensures 24 | ## modules and global scripts declared therein get installed 25 | ## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html 26 | # catkin_python_setup() 27 | 28 | ################################################ 29 | ## Declare ROS messages, services and actions ## 30 | ################################################ 31 | 32 | ## To declare and build messages, services or actions from within this 33 | ## package, follow these steps: 34 | ## * Let MSG_DEP_SET be the set of packages whose message types you use in 35 | ## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). 36 | ## * In the file package.xml: 37 | ## * add a build_depend tag for "message_generation" 38 | ## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET 39 | ## * If MSG_DEP_SET isn't empty the following dependency has been pulled in 40 | ## but can be declared for certainty nonetheless: 41 | ## * add a exec_depend tag for "message_runtime" 42 | ## * In this file (CMakeLists.txt): 43 | ## * add "message_generation" and every package in MSG_DEP_SET to 44 | ## find_package(catkin REQUIRED COMPONENTS ...) 45 | ## * add "message_runtime" and every package in MSG_DEP_SET to 46 | ## catkin_package(CATKIN_DEPENDS ...) 47 | ## * uncomment the add_*_files sections below as needed 48 | ## and list every .msg/.srv/.action file to be processed 49 | ## * uncomment the generate_messages entry below 50 | ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) 51 | 52 | ## Generate messages in the 'msg' folder 53 | # add_message_files( 54 | # FILES 55 | # Message1.msg 56 | # Message2.msg 57 | # ) 58 | 59 | ## Generate services in the 'srv' folder 60 | # add_service_files( 61 | # FILES 62 | # Service1.srv 63 | # Service2.srv 64 | # ) 65 | 66 | ## Generate actions in the 'action' folder 67 | # add_action_files( 68 | # FILES 69 | # Action1.action 70 | # Action2.action 71 | # ) 72 | 73 | ## Generate added messages and services with any dependencies listed here 74 | # generate_messages( 75 | # DEPENDENCIES 76 | # std_msgs 77 | # ) 78 | 79 | ################################################ 80 | ## Declare ROS dynamic reconfigure parameters ## 81 | ################################################ 82 | 83 | ## To declare and build dynamic reconfigure parameters within this 84 | ## package, follow these steps: 85 | ## * In the file package.xml: 86 | ## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" 87 | ## * In this file (CMakeLists.txt): 88 | ## * add "dynamic_reconfigure" to 89 | ## find_package(catkin REQUIRED COMPONENTS ...) 90 | ## * uncomment the "generate_dynamic_reconfigure_options" section below 91 | ## and list every .cfg file to be processed 92 | 93 | ## Generate dynamic reconfigure parameters in the 'cfg' folder 94 | # generate_dynamic_reconfigure_options( 95 | # cfg/DynReconf1.cfg 96 | # cfg/DynReconf2.cfg 97 | # ) 98 | 99 | ################################### 100 | ## catkin specific configuration ## 101 | ################################### 102 | ## The catkin_package macro generates cmake config files for your package 103 | ## Declare things to be passed to dependent projects 104 | ## INCLUDE_DIRS: uncomment this if your package contains header files 105 | ## LIBRARIES: libraries you create in this project that dependent projects also need 106 | ## CATKIN_DEPENDS: catkin_packages dependent projects also need 107 | ## DEPENDS: system dependencies of this project that dependent projects also need 108 | catkin_package( 109 | INCLUDE_DIRS include 110 | # LIBRARIES ros_control_example 111 | CATKIN_DEPENDS controller_manager roscpp rospy std_msgs std_srvs 112 | # DEPENDS system_lib 113 | ) 114 | 115 | ########### 116 | ## Build ## 117 | ########### 118 | 119 | ## Specify additional locations of header files 120 | ## Your package locations should be listed before other locations 121 | include_directories( 122 | include 123 | ${catkin_INCLUDE_DIRS} 124 | ) 125 | 126 | ## Declare a C++ library 127 | # add_library(${PROJECT_NAME} 128 | # src/${PROJECT_NAME}/ros_control_example.cpp 129 | # ) 130 | 131 | ## Add cmake target dependencies of the library 132 | ## as an example, code may need to be generated before libraries 133 | ## either from message generation or dynamic reconfigure 134 | # add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) 135 | 136 | ## Declare a C++ executable 137 | ## With catkin_make all packages are built within a single CMake context 138 | ## The recommended prefix ensures that target names across packages don't collide 139 | # add_executable(${PROJECT_NAME}_node src/ros_control_example_node.cpp) 140 | 141 | ## Rename C++ executable without prefix 142 | ## The above recommended prefix causes long target names, the following renames the 143 | ## target back to the shorter version for ease of user use 144 | ## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" 145 | # set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") 146 | 147 | ## Add cmake target dependencies of the executable 148 | ## same as for the library above 149 | # add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) 150 | 151 | ## Specify libraries to link a library or executable target against 152 | # target_link_libraries(${PROJECT_NAME}_node 153 | # ${catkin_LIBRARIES} 154 | # ) 155 | 156 | add_executable(single_joint_hardware_interface src/robot_hardware_interface_node.cpp) 157 | #add_dependencies(robot_hardware_interface ${catkin_EXPORTED_TARGETS}) 158 | target_link_libraries(single_joint_hardware_interface ${catkin_LIBRARIES}) 159 | 160 | ############# 161 | ## Install ## 162 | ############# 163 | 164 | # all install targets should use catkin DESTINATION variables 165 | # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html 166 | 167 | ## Mark executable scripts (Python etc.) for installation 168 | ## in contrast to setup.py, you can choose the destination 169 | # install(PROGRAMS 170 | # scripts/my_python_script 171 | # DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 172 | # ) 173 | 174 | ## Mark executables and/or libraries for installation 175 | # install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node 176 | # ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 177 | # LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 178 | # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 179 | # ) 180 | 181 | ## Mark cpp header files for installation 182 | # install(DIRECTORY include/${PROJECT_NAME}/ 183 | # DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 184 | # FILES_MATCHING PATTERN "*.h" 185 | # PATTERN ".svn" EXCLUDE 186 | # ) 187 | 188 | ## Mark other files for installation (e.g. launch and bag files, etc.) 189 | # install(FILES 190 | # # myfile1 191 | # # myfile2 192 | # DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 193 | # ) 194 | 195 | ############# 196 | ## Testing ## 197 | ############# 198 | 199 | ## Add gtest based cpp test target and link libraries 200 | # catkin_add_gtest(${PROJECT_NAME}-test test/test_ros_control_example.cpp) 201 | # if(TARGET ${PROJECT_NAME}-test) 202 | # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) 203 | # endif() 204 | 205 | ## Add folders to be run by python nosetests 206 | # catkin_add_nosetests(test) 207 | --------------------------------------------------------------------------------