Open mateusnazarioc opened 5 years ago
Thanks for reporting! This exception should not occur..
Which version of ros_canopen
are you using?
A candump would be very helpful to isolate the underlying problem..
I've had some improvements, but can't get past the actual problem.
I'm getting this error on the terminal running the motor_node.launch:
abort60ff#0, reason: Invalid value for parameter (download only). Could not process message
This is my motor_node.launch:
`
<param name="robot_description" textfile="$(find eposmcd_control)/config/urdf.xml"/>
<node name="canopen_motor_node" pkg="canopen_motor_node" type="canopen_motor_node"
output="screen" ns="/eposmcd" respawn= "true" clear_params="true" >
<rosparam command="load" file="$(find eposmcd_control)/config/canopen.yaml" />
</node>
`
All of this happens after calling the _motornode.launch, then doing /driver/init and trying to publish on the topic _/eposmcd/joint1_velocity_controller/command stdmsgs/Float64 "data: 1000.0" after calling the controller.launch.
This is the controller.launch:
<launch>
<!-- Load joint controller configurations from YAML file to parameter server -->
<rosparam file="$(find eposmcd_control)/config/eposmcd.yaml" command="load"/>
<!-- load the controllers -->
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
output="screen" ns="/eposmcd" args="joint1_velocity_controller joint_state_controller"/>
<!-- convert joint states to TF transforms for rviz, etc -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"
respawn="false" output="screen">
<remap from="/joint_states" to="/eposmcd/joint_states" />
</node>
</launch>
And now my updated canopen.yaml:
bus:
device: can0
sync:
interval_ms: 10
overflow: 0
heartbeat:
rate: 500
nodes:
node1:
id: 1
eds_pkg: eposmcd_control
eds_file: eds/eposmcd.eds
defaults: # optional, all defaults can be overwritten per node
motor_allocator: canopen::Motor402::Allocator # select allocator for motor layer
motor_layer: #settings passed to motor layer (plugin-specific)
switching_state: 2 # (Operation_Enable), state for mode switching
pos_to_device: "rint(rad2deg(pos)*1000)" # rad -> mdeg
pos_from_device: "deg2rad(obj6064)/1000" # actual position [mdeg] -> rad
vel_to_device: "rint(rad2deg(vel)*1000)" # rad/s -> mdeg/s
vel_from_device: "deg2rad(obj606C)/1000" # actual velocity [mdeg/s] -> rad/s
eff_to_device: "rint(eff)" # just round to integer
eff_from_device: "1" # unset
And my eposmcd.yaml:
eposmcd:
# Publish all joint states -----------------------------------
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 50
# Position Controllers ---------------------------------------
joint1_velocity_controller:
type: velocity_controllers/JointVelocityController
joint: node1
pid: {p: 100.0, i: 0.01, d: 10.0}
required_drive_mode: 3
I'm attaching a print of all terminals running, including a candump of the port. Thx!
I've had some improvements, but can't get past the actual problem.
What did you change?
I'm attaching a print of all terminals running, including a candump of the port.
Thanks, but I really meant an actual text file, which could get examined properly..
heartbeat: rate: 500
This would be way too high! But it is not used anyway, because it is listed in the sync
block.
abort60ff#0, reason: Invalid value for parameter (download only). Could not process message
Are you sure that you set-up the user units properly? The default is milli degrees, so you would be commanding 57295779
Instead of commanding 1000.0
(in rad!), I would start with something simpler, like 0.0
.
#Position Controllers ---------------------------------------
But you specify a velocity controller..
Hello, guys. I'm having some trouble to make a maxon epos mcd run with ros_canopen. This is the message I'm getting after calling
rosservice call /driver/init
:message: "Throw location unknown (consider using BOOST_THROW_EXCEPTION)\nDynamic exception\ \ type: boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error>\ \ >\nstd::exception::what: boost: mutex lock failed in pthread_mutex_lock: Invalid\ \ argument\n"
And on the terminal running the launch of the motor package:
This is my currently .yaml:
I'm attaching the .eds used. eposmcd.txt __ Thx!