mirror of
https://github.com/OSURoboticsClub/Rover_2017_2018.git
synced 2025-11-08 18:21:15 +00:00
Started adding in xbox controller to gui. Thinking of scrapping spacenav mouse. It kinda sucks. Also, three axes moving on the arm! Time to make an action client for moveitgit add .git add .!
This commit is contained in:
@@ -1,5 +1,6 @@
|
||||
#include <string>
|
||||
#include <iostream>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <ros/ros.h>
|
||||
#include <ros/console.h>
|
||||
@@ -13,8 +14,7 @@ int device_address = 1;
|
||||
|
||||
////////// Global Variables //////////
|
||||
// ROS Parameter Defaults
|
||||
const string default_port = "/dev/ttyUSB0";
|
||||
|
||||
const string default_port = "/dev/rover/ttyARM";
|
||||
|
||||
// Axis Defaults
|
||||
const smint32 axis1_max_count = 100000;
|
||||
@@ -47,6 +47,8 @@ public:
|
||||
if(arm_bus_handle < 0){
|
||||
ROS_ERROR("Could not connect to arm");
|
||||
}
|
||||
|
||||
ROS_INFO("Connected to smBus");
|
||||
}
|
||||
|
||||
void run(){
|
||||
@@ -57,18 +59,40 @@ public:
|
||||
while(ros::ok()){
|
||||
smSetParameter(arm_bus_handle, device_address, SMP_FAULTS, 0);
|
||||
smSetParameter(arm_bus_handle, device_address, SMP_CONTROL_BITS1, SMP_CB1_ENABLE);
|
||||
smSetParameter(arm_bus_handle, 2, SMP_FAULTS, 0);
|
||||
smSetParameter(arm_bus_handle, 2, SMP_CONTROL_BITS1, SMP_CB1_ENABLE);
|
||||
smSetParameter(arm_bus_handle, 3, SMP_FAULTS, 0);
|
||||
smSetParameter(arm_bus_handle, 3, SMP_CONTROL_BITS1, SMP_CB1_ENABLE);
|
||||
|
||||
smint32 status = 0;
|
||||
while(!(status & STAT_TARGET_REACHED)){
|
||||
smRead1Parameter(arm_bus_handle, device_address, SMP_STATUS, &status);
|
||||
smint32 status1 = 0;
|
||||
smint32 status2 = 0;
|
||||
|
||||
smint32 position = 0;
|
||||
smint32 position1 = 0;
|
||||
smint32 position2 = 0;
|
||||
|
||||
smint32 read_bus_voltage;
|
||||
|
||||
while(!(status & STAT_TARGET_REACHED) || !(status1 & STAT_TARGET_REACHED) || !(status2 & STAT_TARGET_REACHED)){
|
||||
smRead2Parameters(arm_bus_handle, device_address, SMP_STATUS, &status, SMP_ACTUAL_POSITION_FB, &position);
|
||||
smRead2Parameters(arm_bus_handle, 2, SMP_STATUS, &status1, SMP_ACTUAL_POSITION_FB, &position1);
|
||||
smRead2Parameters(arm_bus_handle, 3, SMP_STATUS, &status2, SMP_ACTUAL_POSITION_FB, &position2);
|
||||
smRead1Parameter(arm_bus_handle, device_address, SMP_ACTUAL_BUS_VOLTAGE, &read_bus_voltage);
|
||||
|
||||
ROS_INFO("Dir: %u\tVoltage: %ld\tAxis 1: %ld\tAxis 2: %ld\tAxis 3: %ld", dir, read_bus_voltage, position, position1, position2);
|
||||
}
|
||||
|
||||
dir = !dir;
|
||||
|
||||
if(dir){
|
||||
smSetParameter(arm_bus_handle, device_address, SMP_ABSOLUTE_SETPOINT, 0);
|
||||
smSetParameter(arm_bus_handle, 2, SMP_ABSOLUTE_SETPOINT, 0);
|
||||
smSetParameter(arm_bus_handle, 3, SMP_ABSOLUTE_SETPOINT, 0);
|
||||
}else{
|
||||
smSetParameter(arm_bus_handle, device_address, SMP_ABSOLUTE_SETPOINT, 330000);
|
||||
smSetParameter(arm_bus_handle, device_address, SMP_ABSOLUTE_SETPOINT, 50000);
|
||||
smSetParameter(arm_bus_handle, 2, SMP_ABSOLUTE_SETPOINT, 300000);
|
||||
smSetParameter(arm_bus_handle, 3, SMP_ABSOLUTE_SETPOINT, 250000);
|
||||
}
|
||||
|
||||
ros::spinOnce();
|
||||
|
||||
@@ -63,7 +63,7 @@ smbusdevicehandle smBDOpen( const char *devicename )
|
||||
//all handles in use
|
||||
if(handle>=SM_MAX_BUSES) return -1;
|
||||
|
||||
if(strncmp(devicename,"COM",3) == 0 || strncmp(devicename,"/dev/tty",8) == 0) //use rs232 lib
|
||||
if(strncmp(devicename,"COM",3) == 0 || strncmp(devicename,"/dev/tty",8) == 0 || strncmp(devicename,"/dev/rover/tty",8) == 0)
|
||||
{
|
||||
BusDevice[handle].comPort=OpenComport( devicename, SM_BAUDRATE );
|
||||
if( BusDevice[handle].comPort == -1 )
|
||||
|
||||
Reference in New Issue
Block a user