Skip to content

Commit

Permalink
WIP #3: Wrote simple test to read CAN bus voltage
Browse files Browse the repository at this point in the history
  • Loading branch information
Jacob Gloudemans committed Jan 17, 2019
1 parent 5f24c1f commit 22aac74
Show file tree
Hide file tree
Showing 3 changed files with 49 additions and 35 deletions.
8 changes: 2 additions & 6 deletions motor_control/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -77,14 +77,10 @@ else()
endif()

## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide
# add_executable(${PROJECT_NAME}_node src/phoenix_node.cpp)
#add_executable(phoenix_node ${PROJECT_SOURCE_DIR}/example.cpp)
add_executable(example ${PROJECT_SOURCE_DIR}/src/example.cpp)
add_executable(can_bus_interface ${PROJECT_SOURCE_DIR}/src/can_bus_interface.cpp)

## Specify libraries to link a library or executable target against
target_link_libraries(example
target_link_libraries(can_bus_interface
${catkin_LIBRARIES}
Threads::Threads
CTRE_Phoenix CTRE_PhoenixCCI CTRE_PhoenixPlatformLinuxSocketCan CTRE_PhoenixCanutils
Expand Down
47 changes: 47 additions & 0 deletions motor_control/src/can_bus_interface.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@

// General C++ includes
#include <string>
#include <iostream>
#include <chrono>
#include <thread>
#include <algorithm>
#include <cstdint>

// Phoenix libraries
#include "ctre/Phoenix.h"
#include "Platform-linux-socket-can.h"

// ROS libraries
#include "ros/ros.h"
#include "geometry_msgs/Twist.h"

// Global pointers for each motor controller

int main(int argc, char **argv) {

// Initialize ROS node
ros::init(argc, argv, "can_bus_interface");
ros::NodeHandle n;

// Initialize CAN bus
std::string interface = "can0";
ctre::phoenix::platform::can::SetCANInterface(interface.c_str());

// Create a Talon object
ctre::phoenix::motorcontrol::can::TalonSRX fl(1);

ros::Rate loop_rate(1);

// Loop
while (ros::ok())
{
// Read information from the Talon
std::cout << "Current voltage: " << fl.GetBusVoltage() << std::endl;

// Pause at loop rate
loop_rate.sleep();
}


return 0;
}
29 changes: 0 additions & 29 deletions motor_control/src/example.cpp

This file was deleted.

0 comments on commit 22aac74

Please sign in to comment.