Skip to content

Commit

Permalink
commit initial release version with everything working ;-)
Browse files Browse the repository at this point in the history
  • Loading branch information
rbirac committed Feb 2, 2015
0 parents commit 6b560d3
Show file tree
Hide file tree
Showing 10 changed files with 1,334 additions and 0 deletions.
67 changes: 67 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
cmake_minimum_required(VERSION 2.8.3)
project(um7)

find_package(catkin REQUIRED COMPONENTS roscpp serial roslint sensor_msgs
message_generation)

add_service_files(
FILES
Reset.srv
)

generate_messages()

catkin_package(
INCLUDE_DIRS include
CATKIN_DEPENDS message_runtime
)

###########
## Build ##
###########

## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(include
${catkin_INCLUDE_DIRS}
)

## Declare a cpp executable
add_executable(um7_driver src/main.cpp src/registers.cpp src/comms.cpp)
target_link_libraries(um7_driver ${catkin_LIBRARIES} )
add_dependencies(um7_driver um7_generate_messages_cpp)


#############
## Install ##
#############

install(TARGETS um7_driver
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

##########
## Docs ##
##########

file(GLOB LINT_SRCS
src/*.cpp
include/um6/registers.h
include/um6/comms.h)
roslint_cpp(${LINT_SRCS})
roslint_add_test()

#############
## Testing ##
#############

catkin_add_gtest(${PROJECT_NAME}_test_registers test/test_registers.cpp src/registers.cpp)
catkin_add_gtest(${PROJECT_NAME}_test_comms test/test_comms.cpp src/comms.cpp src/registers.cpp)
if(TARGET ${PROJECT_NAME}_test_comms)
target_link_libraries(${PROJECT_NAME}_test_comms util ${catkin_LIBRARIES})
endif()
if(TARGET ${PROJECT_NAME}_test_registers)
target_link_libraries(${PROJECT_NAME}_test_registers util ${catkin_LIBRARIES})
endif()


6 changes: 6 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
ros-drivers-um7
===============

ROS driver for the CH Robotics UM7 inertial measurement device.
Supports standard data and mag topics as well as providing temperature and rpy outputs.
See the ROS wiki for details: (soon to come)
87 changes: 87 additions & 0 deletions include/um7/comms.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,87 @@
/**
*
* \file
* \brief Comms class definition. Does not manage the serial connection
* itself, but takes care of reading and writing to UM7.
* \author Mike Purvis <[email protected]>
* \copyright Copyright (c) 2013, Clearpath Robotics, Inc.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of Clearpath Robotics, Inc. nor the
* names of its contributors may be used to endorse or promote products
* derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL CLEARPATH ROBOTICS, INC. BE LIABLE FOR ANY
* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
* Please send comments, questions, or patches to [email protected]
*
*/

#ifndef INCLUDE_UM7_COMMS_H_
#define INCLUDE_UM7_COMMS_H_

#include <stdint.h>
#include <string>

namespace serial {
class Serial;
}

namespace um7 {

class SerialTimeout : public std::exception {};

class BadChecksum : public std::exception {};

class Registers;
class Accessor_;

class Comms {
public:
explicit Comms(serial::Serial* s) : serial_(s), first_spin_(true) {
}

/**
* Returns -1 if the serial port timed out before receiving a packet
* successfully, or if there was a bad checksum or any other error.
* Otherwise, returns the 8-bit register number of the successfully
* returned packet.
*/
int16_t receive(Registers* r);

void send(const Accessor_& a) const;

bool sendWaitAck(const Accessor_& a);

static const uint8_t PACKET_HAS_DATA;
static const uint8_t PACKET_IS_BATCH;
static const uint8_t PACKET_BATCH_LENGTH_MASK;
static const uint8_t PACKET_BATCH_LENGTH_OFFSET;

static std::string checksum(const std::string& s);

static std::string message(uint8_t address, std::string data);

private:
bool first_spin_;
serial::Serial* serial_;
};
}

#endif // INCLUDE_UM7_COMMS_H_

Loading

0 comments on commit 6b560d3

Please sign in to comment.