Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
30 commits
Select commit Hold shift + click to select a range
108f4ef
Some lint
Tzanccc Apr 11, 2022
54c0807
Finished de-linting ArmMotor
Tzanccc Apr 12, 2022
6de943b
Incomplete de-linting on ArmControlSystem
Tzanccc Apr 12, 2022
f90bf52
mispelling
Tzanccc Apr 12, 2022
88fc9a6
First round de-linting of AbstractJoint
Apr 12, 2022
3904d85
Redo-ing some lint with an additional `clang-tidy` options
bennowotny Apr 12, 2022
5491851
Committing settings for linter. Discussions to be had on whether or …
bennowotny Apr 12, 2022
4a27398
Continuing to work on the `DifferentialJoint` de-linting
bennowotny Apr 12, 2022
3cfa0c9
More differential joint refactoring?
bennowotny Apr 12, 2022
b1836c7
Adding more TODO remarks and modifying method signatures to add `cons…
bennowotny Apr 12, 2022
af2e80f
Formatting
bennowotny Apr 12, 2022
7178e65
Refactoring
Tzanccc Apr 15, 2022
9360c33
Undo changes to settings.json
Tzanccc Apr 15, 2022
d137265
AbstractJoint signature changes.
bennowotny Apr 18, 2022
73b61ef
AbstractJoint de-linting
bennowotny Apr 18, 2022
d96df64
DifferentialJoint de-linted.
bennowotny Apr 18, 2022
6156f6e
De-linting SimpleJoint
Tzanccc Apr 18, 2022
6dc186e
Finished first-pass linting, not building
bennowotny Apr 19, 2022
e3d08a1
Updating to C++17 to resolve static storage issues.
bennowotny Apr 19, 2022
c15e338
Removing unused method/minor refactoring.
bennowotny Apr 20, 2022
b33fb6f
Able to roll back C++ version to auto-deduced 14, resolved linker error.
bennowotny Apr 20, 2022
fc94816
Arm Encoder Tuning
Apr 21, 2022
c020ab7
Updating wrist tracking logic.
bennowotny Apr 21, 2022
5a4ecf2
Updating wrist tracking logic.
bennowotny Apr 21, 2022
a8f009a
Added movit-visual-tools to project.json
Tzanccc Apr 21, 2022
daed11c
Updated pitch math (turns out it was a direct reading all along).
Apr 22, 2022
6dca2fd
Merge branch 'ACS-lint' of ssh://wrover-software.github.com/Wisconsin…
Apr 22, 2022
acb8a8a
Modifying speed handling in the arm and holding PID-enabled/`RUN_TO_P…
bennowotny Apr 22, 2022
5726219
added class headers
Tzanccc Apr 29, 2022
a9c3c96
Removed outdated comments
Tzanccc Apr 29, 2022
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@ devel/
/.vscode/*
# except recommended extensions
!/.vscode/extensions.json
!/.vscode/settings.json

# fetched external libs
# NOTE: these may be removed in the future, tbd
Expand Down
14 changes: 14 additions & 0 deletions .vscode/settings.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
{
"clang-tidy.checks": [
"bugprone-*",
"performance-*",
"readability-*",
"modernize-*",
"hicpp-*",
"cppcoreguidelines-*",
"clang-analyzer-*",
"-readability-braces-around-statements",
"-hicpp-braces-around-statements",
"-cppcoreguidelines-non-private-member-variables-in-classes"
]
}
7 changes: 7 additions & 0 deletions project.json
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,13 @@
"package": "ros-noetic-moveit",
"provider": "apt"
}
},
{
"name": "moveit-visual-tools",
"build": {
"package": "ros-noetic-moveit-visual-tools",
"provider": "apt"
}
}
]
}
2 changes: 1 addition & 1 deletion src/wr_control_drive_arm/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 3.0.2)
cmake_minimum_required(VERSION 3.8)
project(wr_control_drive_arm)

## Compile as C++11, supported in ROS Kinetic and newer
Expand Down
12 changes: 6 additions & 6 deletions src/wr_control_drive_arm/config/encoder_parameters.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -3,17 +3,17 @@ encoder_parameters:
- counts_per_rotation: -2048
offset: 736
# forearm_roll
- counts_per_rotation: 2048
offset: 0
- counts_per_rotation: -2048
offset: 600
# shoulder
- counts_per_rotation: -6144
offset: 460
offset: 1450
# turntable
- counts_per_rotation: 2048
offset: 1111
offset: 736
# wrist_pitch
- counts_per_rotation: 2048
offset: 350
offset: 696
# wrist_roll
- counts_per_rotation: 2048
offset: 1023
offset: 1045
39 changes: 20 additions & 19 deletions src/wr_control_drive_arm/src/AbstractJoint.cpp
Original file line number Diff line number Diff line change
@@ -1,40 +1,41 @@
/**
* @file AbstractJoint.cpp
* @author Nichols Underwood
* @brief ablskjlfkejfs
* @brief Implementation of the AbstractJoint class
* @date 2021-10-25
*/

#include "AbstractJoint.hpp"

AbstractJoint::AbstractJoint(ros::NodeHandle* n, int numMotors){
this->n = n;
this->numMotors = numMotors;

jointPositions.reserve(numMotors);
jointVelocites.reserve(numMotors);

AbstractJoint::AbstractJoint(ros::NodeHandle &n, int numMotors){
this->motors.resize(numMotors);
}

int AbstractJoint::getDegreesOfFreedom(){
return this->numMotors;
auto AbstractJoint::getDegreesOfFreedom() const -> unsigned int{
return this->motors.size();
}

ArmMotor* AbstractJoint::getMotor(int motorIndex){
return this->motors[motorIndex];
auto AbstractJoint::getMotor(int motorIndex) const -> const std::unique_ptr<ArmMotor>&{
return this->motors.at(motorIndex).motor;
}

void AbstractJoint::configSetpoint(int degreeIndex, double position, double velocity){

this->jointPositions[degreeIndex] = position;
this->jointVelocites[degreeIndex] = velocity;
this->motors.at(degreeIndex).position = position;
this->motors.at(degreeIndex).velocity = velocity;
}


bool AbstractJoint::exectute(){
vector<double> motorPositions;
this->getMotorPositions(jointPositions, motorPositions);
for(int i = 0; i < this->numMotors; i++){
if (!this->motors[i]->runToTarget(motorPositions[i], 0)) return false;
auto AbstractJoint::exectute() -> bool{
for(auto &motorHandle : motors){
if (!motorHandle.motor->runToTarget(motorHandle.position, motorHandle.velocity));
return false;
}
return true;
}

void AbstractJoint::stopJoint(){
for(auto &motorHandle : motors){
motorHandle.motor->setPower(0.F);
}
}
55 changes: 29 additions & 26 deletions src/wr_control_drive_arm/src/AbstractJoint.hpp
Original file line number Diff line number Diff line change
@@ -1,43 +1,46 @@
/**
* @file AbstractJoint.hpp
* @author Nichols Underwood
* @brief Header file of the AbstractJoint class
* @date 2021-10-25
*/

#ifndef ABSTRACT_JOINT_GUARD
#define ABSTRACT_JOINT_GUARD

#include "ArmMotor.hpp"
using std::vector;

class AbstractJoint {
public:
struct MotorHandler{
std::unique_ptr<ArmMotor> motor;
double position;
double velocity;
std::string jointTopicName;
std::string motorTopicName;
bool newVelocity;
};

AbstractJoint(ros::NodeHandle &n, int numMotors);

protected:
ros::NodeHandle* n;
unsigned int numMotors;
vector<ArmMotor*> motors;

vector<double> jointPositions;
vector<double> jointVelocites;

vector<std::string> jointTopicsNames;
vector<std::string> motorTopicsNames;
vector<bool> newVelocitiesVector;

public:

AbstractJoint(ros::NodeHandle* n, int numMotors);
~AbstractJoint(){};
// never used, need to be defined for compiler v-table
virtual auto getMotorPositions(const vector<double> &jointPositions) -> vector<double> = 0;
virtual auto getMotorVelocities(const vector<double> &joinVelocities) -> vector<double> = 0;
virtual auto getJointPositions(const vector<double> &motorPositions) -> vector<double> = 0;

// never used, need to be defined for compiler v-table
virtual void getMotorPositions(vector<double> &jointPositions, vector<double> &target) = 0;
virtual void getMotorVelocities(vector<double> &joinVelocities, vector<double> &target) = 0;
virtual void getJointPositions(vector<double> &motorPositions, vector<double> &target) = 0;
auto getDegreesOfFreedom() const -> unsigned int;

auto getMotor(int motorIndex) const -> const std::unique_ptr<ArmMotor>&;

int getDegreesOfFreedom();

ArmMotor* getMotor(int motorIndex);
void configSetpoint(int degreeIndex, double position, double velocity);

void configSetpoint(int degreeIndex, double position, double velocity);
auto exectute() -> bool;

bool exectute();
void stopJoint();

// virtual void configVelocityHandshake(std::string, std::string) = 0;
protected:
vector<MotorHandler> motors;
};

#endif
Loading