roscpp
transmission_interface
urdf
+ voltage_controllers
)
## System dependencies are found with CMake's conventions
catkin_package(
INCLUDE_DIRS include
LIBRARIES gazebo_ros_electrical
-# CATKIN_DEPENDS angles control_toolbox gazebo hardware_interface joint_limits_interface pluginlib roscpp transmission_interface urdf
+# CATKIN_DEPENDS angles control_toolbox gazebo hardware_interface joint_limits_interface pluginlib roscpp transmission_interface urdf voltage_controllers
# DEPENDS system_lib
)
// URDF
#include <urdf/model.h>
-#ifndef HARDWARE_INTERFACE_JOINT_COMMAND_EXTENDED_INTERFACE_H
-#define HARDWARE_INTERFACE_JOINT_COMMAND_EXTENDED_INTERFACE_H
+//Fix this
+#include <voltage_controllers/joint_command_interface.h>
-#include "hardware_interface/joint_command_interface.h"
-
-namespace twil_hardware_interfaces {
-
-/// \ref JointCommandInterface for commanding voltage-based joints.
-class VoltageJointInterface : public hardware_interface::JointCommandInterface {};
-
-}
-
-#endif
-
-namespace hardware_interface
-{
-class VoltageJointInterface : public twil_hardware_interfaces::VoltageJointInterface {};
-}
namespace gazebo_ros_electrical
{
<build_depend>roscpp</build_depend>
<build_depend>transmission_interface</build_depend>
<build_depend>urdf</build_depend>
+ <build_depend>voltage_controllers</build_depend>
<run_depend>angles</run_depend>
<run_depend>control_toolbox</run_depend>
<run_depend>gazebo</run_depend>
<run_depend>roscpp</run_depend>
<run_depend>transmission_interface</run_depend>
<run_depend>urdf</run_depend>
+ <run_depend>voltage_controllers</run_depend>
<!-- The export tag contains other, unspecified, tags -->
if(joint_inductance_[j] > 0.0)
{
- joint_current_[j]+=(voltage-joint_current_[j]*joint_resistance_[j]-joint_torque_constant_[j]*joint_velocity_[j])/joint_inductance_[j]/period.toSec();
+ joint_current_[j]+=(voltage-joint_current_[j]*joint_resistance_[j]-joint_torque_constant_[j]*joint_velocity_[j])/joint_inductance_[j]*period.toSec();
}
else joint_current_[j]=(voltage-joint_torque_constant_[j]*joint_velocity_[j])/joint_resistance_[j];
const double effort=joint_torque_constant_[j]*joint_current_[j];