diff --git a/Dockerfile b/Dockerfile
index fa9e6d0b936d89830f9d81f4e1538e96ada783ef..95b0217babffbf45838eb86a1bc9699ea5b82c72 100644
--- a/Dockerfile
+++ b/Dockerfile
@@ -29,7 +29,7 @@ RUN apt install -y \
 
 # make the environment more usable
 # create user
-RUN useradd -m -s /bin/zsh -G sudo -u 1001 student
+RUN useradd -m -s /bin/zsh -G sudo -u 1000 student
 
 WORKDIR /home/student/
 RUN passwd -d student
diff --git a/TODOS_2024_09_19 b/TODOS_2024_09_19
index 1e083f63a22add8302b66426182af186c23fa809..1c12eb3f18c7901410e674c81bcac4a10a63cf70 100644
--- a/TODOS_2024_09_19
+++ b/TODOS_2024_09_19
@@ -5,6 +5,13 @@ goal 2: clean up the code
                       of a 'session' or at least names all logs in a run)
 3. use python's logging instead of printing
 
+goal 3:
+----------
+enforce simulation first, or at least make it easy to simulate a thing 
+STARTING FROM THE CURRENT ROBOT POSITION while you're connected.
+basically "--simulate-from-current-pose" 
+to the make the "simulate every time before you run maxim" not annoying.
+
 goal 4: more controllers
 ------------------------
 1. finish adding all ik algorithms
@@ -12,9 +19,14 @@ goal 4: more controllers
 3. [hard] adjusting the dmp to get back on the path despite external forces 
    (fix the problem of writing on a non-flat surface/whatever) --> publishable side-project
 
+goal 5:
+-------
+include the workspace somehow
+
 finally, do what you promised and put this on another robot,
 thereby rendering this something publishable in joss
 
 goal 5: panda/yumi
 ----------------
 1. transfer the library to panda or yumi or both
+
diff --git a/docs/installation.md b/docs/installation.md
index 32c1b581584f4d072dac1726c6386775ffec6c3d..f0ef86a4d75ba58a4c0d76eb7d626a5a1d377a6f 100644
--- a/docs/installation.md
+++ b/docs/installation.md
@@ -3,8 +3,8 @@
 In the interest of time, the library is shipped as a Docker image.
 
 Installing docker on windows:
-1. install wsl with "wsl --install" in powershell administrator, more at https://learn.microsoft.com/en-us/windows/wsl/install
-2. install docker on windows (with wsl option, should be default)
+1. install wsl with "wsl --install" in powershell administrator, more at [windows docs](https://learn.microsoft.com/en-us/windows/wsl/install)
+2. install docker on windows (with wsl option, should be default), more at [docker docs](https://docs.docker.com/desktop/install/windows-install)
 3. create the docker accout 
 4. open docker desktop, navigate to Settings (by user/account button) -> Resources -> Network -> click on enable host networking
 5. open wsl (type wsl in powershell) and navigate to git folder (now in wsl) with "cd /mnt/Users/YOURUSERNAME/PATH_TO_GIT_FOLDER"
diff --git a/python/ur_simple_control/clik/clik_point_to_point.py b/python/ur_simple_control/clik/clik_point_to_point.py
index 838a917e91bf7ba5b1ed908118d7f573d7e4b839..514613736a71a71285d7aaa8b68468299ef04269 100644
--- a/python/ur_simple_control/clik/clik_point_to_point.py
+++ b/python/ur_simple_control/clik/clik_point_to_point.py
@@ -167,7 +167,6 @@ def controlLoopClik(robot, clik_controller, i, past_data):
     log_item = {}
     # know where you are, i.e. do forward kinematics
     q = robot.getQ()
-    pin.forwardKinematics(robot.model, robot.data, q)
     # first check whether we're at the goal
     SEerror = robot.data.oMi[robot.JOINT_ID].actInv(robot.Mgoal)
     err_vector = pin.log6(SEerror).vector 
@@ -175,6 +174,7 @@ def controlLoopClik(robot, clik_controller, i, past_data):
 #      print("Convergence achieved, reached destionation!")
         breakFlag = True
     # pin.computeJointJacobian is much different than the C++ version lel
+    # TODO: put in step, havew getter for it
     J = pin.computeJointJacobian(robot.model, robot.data, q, robot.JOINT_ID)
     # compute the joint velocities.
     # just plug and play different ones
@@ -211,7 +211,6 @@ def moveUntilContactControlLoop(contact_detecting_force, speed, robot, clik_cont
     breakFlag = False
     # know where you are, i.e. do forward kinematics
     q = robot.getQ()
-    pin.forwardKinematics(robot.model, robot.data, q)
     # break if wrench is nonzero basically
     #wrench = robot.getWrench()
     # you're already giving the speed in the EE i.e. body frame
diff --git a/python/ur_simple_control/visualize/manipulator_visual_motion_analyzer.py b/python/ur_simple_control/visualize/manipulator_visual_motion_analyzer.py
index 2abb22effaa6a666ddfc93390550448fab3057f4..280709b4b2a5feab1e5225782403661bc60dacec 100644
--- a/python/ur_simple_control/visualize/manipulator_visual_motion_analyzer.py
+++ b/python/ur_simple_control/visualize/manipulator_visual_motion_analyzer.py
@@ -144,10 +144,10 @@ class ManipulatorVisualMotionAnalyzer:
         screensize = pyautogui.size()
         self.SCREEN_WIDTH = screensize.width
         self.SCREEN_HEIGHT = screensize.height
-        self.SCALING_FACTOR_HEIGHT = 0.8
+        #self.SCALING_FACTOR_HEIGHT = 0.8
+        #self.SCALING_FACTOR_WIDTH = 0.5
+        self.SCALING_FACTOR_HEIGHT = 0.35
         self.SCALING_FACTOR_WIDTH = 0.5
-        #self.SCALING_FACTOR_HEIGHT = 0.3
-        #self.SCALING_FACTOR_WIDTH = 0.3
         # dicts not because they have to be, but just so that
         # they are named because that might be useful
         # and because names are the only thing keeping horrendous this code together